Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Arduplane/quadplane.cpp: shut down motors when parachute released #14273

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 12 additions & 0 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1856,6 +1856,18 @@ void QuadPlane::update(void)
*/
void QuadPlane::update_throttle_suppression(void)
{
#if PARACHUTE == ENABLED
// if parachute has been released shut down motors
if (plane.parachute.release_initiated()) {
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);

// set throttle to 0 for correct last_motors_active_ms behaviour
motors->set_throttle(0);
last_motors_active_ms = 0;
return;
}
#endif

// if the motors have been running in the last 2 seconds then
// allow them to run now
if (AP_HAL::millis() - last_motors_active_ms < 2000) {
Expand Down