Solved this by just digging through the code. TLDR - delete the PX4-Autopilot/build
and build again with make px4_sitl gazebo_standard_vtol
Anyway –
- The Factory Reset button sends a mavlink command to reset the factory parameters in
SensorComponentController.cc
in QGroundControl:
_vehicle->sendMavCommand(compId,
MAV_CMD_PREFLIGHT_STORAGE,
true, // showError
3, // Reset factory parameters
-1); // Don't do anything with mission storage
- The
Commander.cpp
in PX4 receives the command and dispatches a job to execute the command
} else if (((int)(cmd.param1)) == 3) {
answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED);
_worker_thread.startTask(WorkerThread::Request::ParamResetSensorFactory);
}
- The
worker_thread.cpp
in PX4 writes the changes to a parameters file kept in the aircraft’s eeprom
case Request::ParamResetSensorFactory:
const char *reset_cal[] = { "CAL_ACC*", "CAL_GYRO*", "CAL_MAG*" };
param_reset_specific(reset_cal, sizeof(reset_cal) / sizeof(reset_cal[0]));
_ret_value = param_save_default();
#if defined(CONFIG_BOARDCTL_RESET)
px4_reboot_request(false, 400_ms);
#endif // CONFIG_BOARDCTL_RESET
break;
}
It appears that for SITL, this eeprom record is persisted across builds. One can manually locate that file or, simply remove the PX4-Autopilot/build/
directory in PX4-Autopilot repo. Apparently a make clean
is not sufficient. Then just build from scratch with make px4_sitl gazebo_standard_vtol
.