feat(commander): accept optional heading arg for mag quick calibration (#24637)

* Update Mag quick Cal to accept heading arguments

* Fixed formatting

* Update src/modules/commander/Commander.cpp

Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>

* Update src/modules/commander/Commander.cpp

---------

Co-authored-by: Jacob Dahl <37091262+dakejahl@users.noreply.github.com>
This commit is contained in:
Ryan Johnston
2026-04-28 01:46:53 -07:00
committed by GitHub
parent e0a9572e1c
commit 622e72c26a
+24 -2
View File
@@ -249,8 +249,30 @@ int Commander::custom_command(int argc, char *argv[])
} else if (!strcmp(argv[1], "mag")) {
if (argc > 2 && (strcmp(argv[2], "quick") == 0)) {
// magnetometer quick calibration: VEHICLE_CMD_FIXED_MAG_CAL_YAW
send_vehicle_command(vehicle_command_s::VEHICLE_CMD_FIXED_MAG_CAL_YAW);
// Magnetometer quick calibration with optional heading
float heading_deg = 0.0f;
if (argc > 3) {
char *end;
heading_deg = strtof(argv[3], &end);
if (*end != '\0') { // Check if parsing failed
PX4_ERR("Invalid heading value: %s", argv[3]);
return 1;
}
heading_deg = matrix::wrap(roundf(heading_deg), 0.f, 360.f);
}
// Send command with heading (param1), other params zeroed (use GPS)
send_vehicle_command(vehicle_command_s::VEHICLE_CMD_FIXED_MAG_CAL_YAW,
heading_deg, // param1: Yaw of vehicle in earth frame (deg)
0.0f, // param2: CompassMask, 0 for all
0.0f, // param3: latitude (deg) If Latitude and longitude are both zero then use the current vehicle location
0.0f, // param4: longitude (deg)
0.0, // param5: unused
0.0, // param6: unused
0.0f); // param7: unused
} else {
// magnetometer calibration: param2 = 1