mirror of https://github.com/ArduPilot/ardupilot
Copter: added in sink rate for parachute check
This commit is contained in:
parent
c710002bc9
commit
55dca5cda9
|
@ -201,6 +201,9 @@ void Copter::parachute_check()
|
|||
// release parachute
|
||||
parachute_release();
|
||||
}
|
||||
|
||||
// pass sink rate to parachute library
|
||||
parachute.set_sink_rate(-inertial_nav.get_velocity_z() * 0.01);
|
||||
}
|
||||
|
||||
// parachute_release - trigger the release of the parachute, disarm the motors and notify the user
|
||||
|
|
Loading…
Reference in New Issue