|
|
|
@ -1098,6 +1098,19 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
@@ -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; |
|
|
|
|