Copter: add exit() method to Mode class
This commit is contained in:
parent
278593a6a0
commit
c42681f4f2
@ -328,24 +328,6 @@ void Copter::update_flight_mode()
|
||||
void Copter::exit_mode(Mode *&old_flightmode,
|
||||
Mode *&new_flightmode)
|
||||
{
|
||||
#if AUTOTUNE_ENABLED == ENABLED
|
||||
if (old_flightmode == &mode_autotune) {
|
||||
mode_autotune.stop();
|
||||
}
|
||||
#endif
|
||||
|
||||
// stop mission when we leave auto mode
|
||||
#if MODE_AUTO_ENABLED == ENABLED
|
||||
if (old_flightmode == &mode_auto) {
|
||||
if (mode_auto.mission.state() == AP_Mission::MISSION_RUNNING) {
|
||||
mode_auto.mission.stop();
|
||||
}
|
||||
#if HAL_MOUNT_ENABLED
|
||||
camera_mount.set_mode_to_default();
|
||||
#endif // HAL_MOUNT_ENABLED
|
||||
}
|
||||
#endif
|
||||
|
||||
// smooth throttle transition when switching from manual to automatic flight modes
|
||||
if (old_flightmode->has_manual_throttle() && !new_flightmode->has_manual_throttle() && motors->armed() && !ap.land_complete) {
|
||||
// this assumes all manual flight modes use get_pilot_desired_throttle to translate pilot input to output throttle
|
||||
@ -355,30 +337,8 @@ void Copter::exit_mode(Mode *&old_flightmode,
|
||||
// cancel any takeoffs in progress
|
||||
old_flightmode->takeoff_stop();
|
||||
|
||||
#if MODE_SMARTRTL_ENABLED == ENABLED
|
||||
// call smart_rtl cleanup
|
||||
if (old_flightmode == &mode_smartrtl) {
|
||||
mode_smartrtl.exit();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if MODE_FOLLOW_ENABLED == ENABLED
|
||||
if (old_flightmode == &mode_follow) {
|
||||
mode_follow.exit();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if MODE_ZIGZAG_ENABLED == ENABLED
|
||||
if (old_flightmode == &mode_zigzag) {
|
||||
mode_zigzag.exit();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if MODE_ACRO_ENABLED == ENABLED
|
||||
if (old_flightmode == &mode_acro) {
|
||||
mode_acro.exit();
|
||||
}
|
||||
#endif
|
||||
// perform cleanup required for each flight mode
|
||||
old_flightmode->exit();
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// firmly reset the flybar passthrough to false when exiting acro mode.
|
||||
|
@ -52,6 +52,7 @@ public:
|
||||
virtual bool init(bool ignore_checks) {
|
||||
return true;
|
||||
}
|
||||
virtual void exit() {};
|
||||
virtual void run() = 0;
|
||||
virtual bool requires_GPS() const = 0;
|
||||
virtual bool has_manual_throttle() const = 0;
|
||||
@ -275,7 +276,7 @@ public:
|
||||
bool allows_arming(AP_Arming::Method method) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool init(bool ignore_checks) override;
|
||||
void exit();
|
||||
void exit() override;
|
||||
// whether an air-mode aux switch has been toggled
|
||||
void air_mode_aux_changed();
|
||||
bool allows_save_trim() const override { return true; }
|
||||
@ -350,6 +351,7 @@ public:
|
||||
Number mode_number() const override { return Number::AUTO; }
|
||||
|
||||
bool init(bool ignore_checks) override;
|
||||
void exit() override;
|
||||
void run() override;
|
||||
|
||||
bool requires_GPS() const override { return true; }
|
||||
@ -567,6 +569,7 @@ public:
|
||||
Number mode_number() const override { return Number::AUTOTUNE; }
|
||||
|
||||
bool init(bool ignore_checks) override;
|
||||
void exit() override;
|
||||
void run() override;
|
||||
|
||||
bool requires_GPS() const override { return false; }
|
||||
@ -575,7 +578,6 @@ public:
|
||||
bool is_autopilot() const override { return false; }
|
||||
|
||||
void save_tuning_gains();
|
||||
void stop();
|
||||
void reset();
|
||||
|
||||
protected:
|
||||
@ -1217,7 +1219,7 @@ public:
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
||||
void save_position();
|
||||
void exit();
|
||||
void exit() override;
|
||||
|
||||
bool is_landing() const override;
|
||||
|
||||
@ -1478,7 +1480,7 @@ public:
|
||||
Number mode_number() const override { return Number::FOLLOW; }
|
||||
|
||||
bool init(bool ignore_checks) override;
|
||||
void exit();
|
||||
void exit() override;
|
||||
void run() override;
|
||||
|
||||
bool requires_GPS() const override { return true; }
|
||||
@ -1521,7 +1523,7 @@ public:
|
||||
} zigzag_direction;
|
||||
|
||||
bool init(bool ignore_checks) override;
|
||||
void exit();
|
||||
void exit() override;
|
||||
void run() override;
|
||||
|
||||
// auto control methods. copter flies grid pattern
|
||||
|
@ -55,6 +55,17 @@ bool ModeAuto::init(bool ignore_checks)
|
||||
}
|
||||
}
|
||||
|
||||
// stop mission when we leave auto mode
|
||||
void ModeAuto::exit()
|
||||
{
|
||||
if (copter.mode_auto.mission.state() == AP_Mission::MISSION_RUNNING) {
|
||||
copter.mode_auto.mission.stop();
|
||||
}
|
||||
#if HAL_MOUNT_ENABLED
|
||||
copter.camera_mount.set_mode_to_default();
|
||||
#endif // HAL_MOUNT_ENABLED
|
||||
}
|
||||
|
||||
// auto_run - runs the auto controller
|
||||
// should be called at 100hz or more
|
||||
void ModeAuto::run()
|
||||
|
@ -139,7 +139,7 @@ void ModeAutoTune::save_tuning_gains()
|
||||
autotune.save_tuning_gains();
|
||||
}
|
||||
|
||||
void ModeAutoTune::stop()
|
||||
void ModeAutoTune::exit()
|
||||
{
|
||||
autotune.stop();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user