Browse Source

Copter: added in sink rate for parachute check

master
Andrew Tridgell 6 years ago
parent
commit
55dca5cda9
  1. 3
      ArduCopter/crash_check.cpp

3
ArduCopter/crash_check.cpp

@ -201,6 +201,9 @@ void Copter::parachute_check() @@ -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…
Cancel
Save