mirror of https://github.com/ArduPilot/ardupilot
Plane: Reset TECS along with other controllers
This commit is contained in:
parent
775fab505d
commit
016a81bc14
|
@ -255,6 +255,9 @@ void Mode::reset_controllers()
|
||||||
// reset steering controls
|
// reset steering controls
|
||||||
plane.steer_state.locked_course = false;
|
plane.steer_state.locked_course = false;
|
||||||
plane.steer_state.locked_course_err = 0;
|
plane.steer_state.locked_course_err = 0;
|
||||||
|
|
||||||
|
// reset TECS
|
||||||
|
plane.TECS_controller.reset();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Mode::is_taking_off() const
|
bool Mode::is_taking_off() const
|
||||||
|
|
|
@ -81,7 +81,7 @@ public:
|
||||||
// returns true if the vehicle can be armed in this mode
|
// returns true if the vehicle can be armed in this mode
|
||||||
bool pre_arm_checks(size_t buflen, char *buffer) const;
|
bool pre_arm_checks(size_t buflen, char *buffer) const;
|
||||||
|
|
||||||
// Reset rate and steering controllers
|
// Reset rate and steering and TECS controllers
|
||||||
void reset_controllers();
|
void reset_controllers();
|
||||||
|
|
||||||
//
|
//
|
||||||
|
|
Loading…
Reference in New Issue