Skip to content

Commit

Permalink
Plane: Reset TECS along with other controllers
Browse files Browse the repository at this point in the history
  • Loading branch information
Georacer committed Oct 15, 2024
1 parent 81768b2 commit 9db8b8d
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 1 deletion.
3 changes: 3 additions & 0 deletions ArduPlane/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -255,6 +255,9 @@ void Mode::reset_controllers()
// reset steering controls
plane.steer_state.locked_course = false;
plane.steer_state.locked_course_err = 0;

// reset TECS
plane.TECS_controller.reset();
}

bool Mode::is_taking_off() const
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class Mode
// returns true if the vehicle can be armed in this mode
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();

//
Expand Down

0 comments on commit 9db8b8d

Please sign in to comment.