Browse Source

Plane: revert auto_state.checked_for_autoland back to Plane

mission-4.1.18
Tom Pittenger 8 years ago committed by Tom Pittenger
parent
commit
fc2f518f31
  1. 8
      ArduPlane/ArduPlane.cpp
  2. 3
      ArduPlane/Plane.h
  3. 2
      ArduPlane/system.cpp
  4. 3
      libraries/AP_Landing/AP_Landing.h

8
ArduPlane/ArduPlane.cpp

@ -798,7 +798,7 @@ void Plane::update_navigation() @@ -798,7 +798,7 @@ void Plane::update_navigation()
set_mode(QRTL, MODE_REASON_UNKNOWN);
break;
} else if (g.rtl_autoland == 1 &&
!landing.checked_for_autoland &&
!auto_state.checked_for_autoland &&
reached_loiter_target() &&
labs(altitude_error_cm) < 1000) {
// we've reached the RTL point, see if we have a landing sequence
@ -809,10 +809,10 @@ void Plane::update_navigation() @@ -809,10 +809,10 @@ void Plane::update_navigation()
// prevent running the expensive jump_to_landing_sequence
// on every loop
landing.checked_for_autoland = true;
auto_state.checked_for_autoland = true;
}
else if (g.rtl_autoland == 2 &&
!landing.checked_for_autoland) {
!auto_state.checked_for_autoland) {
// Go directly to the landing sequence
if (landing.jump_to_landing_sequence()) {
// switch from RTL -> AUTO
@ -821,7 +821,7 @@ void Plane::update_navigation() @@ -821,7 +821,7 @@ void Plane::update_navigation()
// prevent running the expensive jump_to_landing_sequence
// on every loop
landing.checked_for_autoland = true;
auto_state.checked_for_autoland = true;
}
radius = abs(g.rtl_radius);
if (radius > 0) {

3
ArduPlane/Plane.h

@ -472,6 +472,9 @@ private: @@ -472,6 +472,9 @@ private:
// in FBWA taildragger takeoff mode
bool fbwa_tdrag_takeoff_mode:1;
// have we checked for an auto-land?
bool checked_for_autoland:1;
// Altitude threshold to complete a takeoff command in autonomous modes. Centimeters
// are we in idle mode? used for balloon launch to stop servo
// movement until altitude is reached

2
ArduPlane/system.cpp

@ -335,7 +335,7 @@ void Plane::set_mode(enum FlightMode mode, mode_reason_t reason) @@ -335,7 +335,7 @@ void Plane::set_mode(enum FlightMode mode, mode_reason_t reason)
auto_state.next_wp_no_crosstrack = true;
// reset landing check
landing.checked_for_autoland = false;
auto_state.checked_for_autoland = false;
// reset go around command
landing.commanded_go_around = false;

3
libraries/AP_Landing/AP_Landing.h

@ -102,9 +102,6 @@ public: @@ -102,9 +102,6 @@ public:
// once landed, post some landing statistics to the GCS
bool post_stats;
// have we checked for an auto-land?
bool checked_for_autoland;
// denotes if a go-around has been commanded for landing
bool commanded_go_around;

Loading…
Cancel
Save