ArduPlane: correct Mission Reset override behaviour in Plane

This commit is contained in:
Hwurzburg 2021-08-05 08:46:05 -05:00 committed by Andrew Tridgell
parent e680611324
commit 80b4cd7ae9
3 changed files with 1 additions and 8 deletions

View File

@ -135,11 +135,6 @@ void RC_Channel_Plane::do_aux_function_flare(AuxSwitchPos ch_flag)
}
}
void RC_Channel_Plane::do_aux_function_mission_reset(const AuxSwitchPos ch_flag)
{
plane.mission.start();
plane.prev_WP_loc = plane.current_loc;
}
void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
const RC_Channel::AuxSwitchPos ch_flag)

View File

@ -26,8 +26,6 @@ private:
void do_aux_function_flare(AuxSwitchPos ch_flag);
void do_aux_function_mission_reset(const AuxSwitchPos ch_flag) override;
};
class RC_Channels_Plane : public RC_Channels

View File

@ -297,7 +297,7 @@ protected:
void do_aux_function_clear_wp(const AuxSwitchPos ch_flag);
void do_aux_function_gripper(const AuxSwitchPos ch_flag);
void do_aux_function_lost_vehicle_sound(const AuxSwitchPos ch_flag);
virtual void do_aux_function_mission_reset(const AuxSwitchPos ch_flag);
void do_aux_function_mission_reset(const AuxSwitchPos ch_flag);
void do_aux_function_rc_override_enable(const AuxSwitchPos ch_flag);
void do_aux_function_relay(uint8_t relay, bool val);
void do_aux_function_sprayer(const AuxSwitchPos ch_flag);