Browse Source

Copter: sipport MAV_CMD_ACCELCAL_VEHICLE_POS

mission-4.1.18
Francisco Ferreira 8 years ago committed by Tom Pittenger
parent
commit
84436ff5ae
  1. 8
      ArduCopter/GCS_Mavlink.cpp

8
ArduCopter/GCS_Mavlink.cpp

@ -1498,6 +1498,14 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) @@ -1498,6 +1498,14 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
break;
}
case MAV_CMD_ACCELCAL_VEHICLE_POS:
result = MAV_RESULT_FAILED;
if (copter.ins.get_acal()->gcs_vehicle_position(packet.param1)) {
result = MAV_RESULT_ACCEPTED;
}
break;
default:
result = MAV_RESULT_UNSUPPORTED;
break;

Loading…
Cancel
Save