|
|
|
@ -1499,8 +1499,25 @@ void GCS_MAVLINK_Plane::handle_rc_channels_override(const mavlink_message_t &msg
@@ -1499,8 +1499,25 @@ void GCS_MAVLINK_Plane::handle_rc_channels_override(const mavlink_message_t &msg
|
|
|
|
|
GCS_MAVLINK::handle_rc_channels_override(msg); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_long_t &packet) |
|
|
|
|
{ |
|
|
|
|
const MAV_RESULT result = GCS_MAVLINK::handle_command_do_set_mission_current(packet); |
|
|
|
|
if (result != MAV_RESULT_ACCEPTED) { |
|
|
|
|
return result; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// if you change this you must change handle_mission_set_current
|
|
|
|
|
plane.auto_state.next_wp_crosstrack = false; |
|
|
|
|
if (plane.control_mode == &plane.mode_auto && plane.mission.state() == AP_Mission::MISSION_STOPPED) { |
|
|
|
|
plane.mission.resume(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return result; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void GCS_MAVLINK_Plane::handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg) |
|
|
|
|
{ |
|
|
|
|
// if you change this you must change handle_command_do_set_mission_current
|
|
|
|
|
plane.auto_state.next_wp_crosstrack = false; |
|
|
|
|
GCS_MAVLINK::handle_mission_set_current(mission, msg); |
|
|
|
|
if (plane.control_mode == &plane.mode_auto && plane.mission.state() == AP_Mission::MISSION_STOPPED) { |
|
|
|
|