Browse Source

Copter: Disable Prec Land State Machine when Prec Land disabled

gps-1.3.1
Rishabh 4 years ago committed by Randy Mackay
parent
commit
40adad743e
  1. 18
      ArduCopter/mode.cpp
  2. 2
      ArduCopter/mode.h
  3. 8
      ArduCopter/mode_auto.cpp
  4. 14
      ArduCopter/mode_land.cpp
  5. 8
      ArduCopter/mode_rtl.cpp

18
ArduCopter/mode.cpp

@ -699,6 +699,24 @@ void Mode::land_run_horizontal_control() @@ -699,6 +699,24 @@ void Mode::land_run_horizontal_control()
}
}
// Do normal landing or precision landing if enabled. pause_descent is true if vehicle should not descend
void Mode::execute_landing(bool pause_descent)
{
#if PRECISION_LANDING == ENABLED
if (pause_descent || !copter.precland.enabled()) {
// we don't want to start descending immediately or prec land is disabled
// in both cases just run simple land controllers
run_land_controllers(pause_descent);
} else {
// prec land is enabled and we have not paused descent
// the state machine takes care of the entire prec landing procedure
run_precland();
}
#else
run_land_controllers(pause_descent);
#endif
}
#if PRECISION_LANDING == ENABLED
// Go towards a position commanded by prec land state machine in order to retry landing
// The passed in location is expected to be NED and in m

2
ArduCopter/mode.h

@ -119,6 +119,8 @@ protected: @@ -119,6 +119,8 @@ protected:
land_run_horizontal_control();
land_run_vertical_control(pause_descent);
}
// Do normal landing or precision landing if enabled. pause_descent is true if vehicle should not descend
void execute_landing(bool pause_descent = false);
// return expected input throttle setting to hover:
virtual float throttle_hover() const;

8
ArduCopter/mode_auto.cpp

@ -889,12 +889,8 @@ void ModeAuto::land_run() @@ -889,12 +889,8 @@ void ModeAuto::land_run()
// set motors to full range
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
#if PRECISION_LANDING == ENABLED
// the state machine takes care of the entire landing procedure
run_precland();
#else
run_land_controllers();
#endif
// run normal landing or precision landing (if enabled)
execute_landing();
}
// auto_rtl_run - rtl in AUTO flight mode

14
ArduCopter/mode_land.cpp

@ -83,17 +83,9 @@ void ModeLand::gps_run() @@ -83,17 +83,9 @@ void ModeLand::gps_run()
if (land_pause && millis()-land_start_time >= LAND_WITH_DELAY_MS) {
land_pause = false;
}
#if PRECISION_LANDING == ENABLED
// the state machine takes care of the entire landing procedure except for land_pause.
if (land_pause) {
// we don't want to start descending immediately
run_land_controllers(true);
} else {
run_precland();
}
#else
run_land_controllers(land_pause);
#endif
// run normal landing or precision landing (if enabled)
execute_landing(land_pause);
}
}

8
ArduCopter/mode_rtl.cpp

@ -413,12 +413,8 @@ void ModeRTL::land_run(bool disarm_on_land) @@ -413,12 +413,8 @@ void ModeRTL::land_run(bool disarm_on_land)
// set motors to full range
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
#if PRECISION_LANDING == ENABLED
// the state machine takes care of the entire landing procedure
run_precland();
#else
run_land_controllers();
#endif
// run normal landing or precision landing (if enabled)
execute_landing();
}
void ModeRTL::build_path()

Loading…
Cancel
Save