Plane: Add MAVLink message handler for CMD_DO_CHANGE_SPEED

This commit is contained in:
Michael Day 2016-05-06 13:27:54 -04:00 committed by Tom Pittenger
parent 62a7074dd7
commit b096e1404d
1 changed files with 10 additions and 0 deletions

View File

@ -1266,6 +1266,16 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
switch(packet.command) { switch(packet.command) {
case MAV_CMD_DO_CHANGE_SPEED:
result = MAV_RESULT_FAILED;
AP_Mission::Mission_Command cmd;
if (AP_Mission::mavlink_cmd_long_to_mission_cmd(packet, cmd)
== MAV_MISSION_ACCEPTED) {
plane.do_change_speed(cmd);
result = MAV_RESULT_ACCEPTED;
}
break;
case MAV_CMD_START_RX_PAIR: case MAV_CMD_START_RX_PAIR:
// initiate bind procedure // initiate bind procedure
if (!hal.rcin->rc_bind(packet.param1)) { if (!hal.rcin->rc_bind(packet.param1)) {