mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Copter: handle MAV_CMD_ACCELCAL_VEHICLE_POS in GCS base class
This commit is contained in:
parent
e85ca5856c
commit
819d892baf
@ -995,12 +995,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
case MAV_CMD_ACCELCAL_VEHICLE_POS:
|
||||
if (!copter.ins.get_acal()->gcs_vehicle_position(packet.param1)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_long_packet(packet);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user