Copter: accept DO_CHANGE_SPEED outside of missions

https://github.com/diydrones/ardupilot/issues/1095
This commit is contained in:
Valentin Brossard 2014-05-29 17:04:53 +02:00 committed by Randy Mackay
parent fd9502d3fa
commit 9fcfea5404
1 changed files with 13 additions and 0 deletions

View File

@ -1098,6 +1098,19 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
}
break;
case MAV_CMD_DO_CHANGE_SPEED:
// param1 : unused
// param2 : new speed in m/s
// param3 : unused
// param4 : unused
if (packet.param2 > 0.0f) {
wp_nav.set_speed_xy(packet.param2 * 100.0f);
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
}
break;
case MAV_CMD_MISSION_START:
if (set_mode(AUTO)) {
result = MAV_RESULT_ACCEPTED;