Browse Source

Plane: override mission-changing-command to reset some state

c415-sdk
Peter Barker 4 years ago committed by Peter Barker
parent
commit
f85e55a611
  1. 17
      ArduPlane/GCS_Mavlink.cpp
  2. 1
      ArduPlane/GCS_Mavlink.h

17
ArduPlane/GCS_Mavlink.cpp

@ -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) {

1
ArduPlane/GCS_Mavlink.h

@ -23,6 +23,7 @@ protected: @@ -23,6 +23,7 @@ protected:
MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_long_t &packet) override;
MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet) override;
MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet) override;
MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet) override;
void send_position_target_global_int() override;

Loading…
Cancel
Save