mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-06 16:03:58 -04:00
Tracker: support MAV_CMD_ACCELCAL_VEHICLE_POS
This commit is contained in:
parent
e870c4bf99
commit
2879e78230
@ -680,6 +680,14 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg)
|
|||||||
result = tracker.compass.handle_mag_cal_command(packet);
|
result = tracker.compass.handle_mag_cal_command(packet);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MAV_CMD_ACCELCAL_VEHICLE_POS:
|
||||||
|
result = MAV_RESULT_FAILED;
|
||||||
|
|
||||||
|
if (tracker.ins.get_acal()->gcs_vehicle_position(packet.param1)) {
|
||||||
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user