GCS_MAVLink: handle MAV_CMD_ACCELCAL_VEHICLE_POS in GCS base class

This commit is contained in:
Peter Barker 2018-07-04 13:43:07 +10:00 committed by Peter Barker
parent d077723028
commit 3710c50c4e
2 changed files with 12 additions and 0 deletions

View File

@ -355,6 +355,7 @@ protected:
virtual MAV_RESULT _handle_command_preflight_calibration_baro();
void handle_command_long(mavlink_message_t* msg);
MAV_RESULT handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_mag_cal(const mavlink_command_long_t &packet);
virtual MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet);
MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet);

View File

@ -2689,12 +2689,23 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(const mavlink_command_long_t &
return result;
}
MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet)
{
if (!AP::ins().get_acal()->gcs_vehicle_position(packet.param1)) {
return MAV_RESULT_FAILED;
}
return MAV_RESULT_ACCEPTED;
}
MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t &packet)
{
MAV_RESULT result = MAV_RESULT_FAILED;
switch (packet.command) {
case MAV_CMD_ACCELCAL_VEHICLE_POS:
result = handle_command_accelcal_vehicle_pos(packet);
case MAV_CMD_DO_SET_MODE:
result = handle_command_do_set_mode(packet);
break;