Copter: integrate parachute check_sink_rate

also move set_is_flying into check parachute to increase it's update rate
This commit is contained in:
Randy Mackay 2020-09-16 15:22:17 +09:00 committed by Andrew Tridgell
parent 4b7709f11d
commit e2d41a3e04
2 changed files with 9 additions and 7 deletions

View File

@ -517,10 +517,6 @@ void Copter::one_hz_loop()
adsb.set_is_flying(!ap.land_complete); adsb.set_is_flying(!ap.land_complete);
#endif #endif
#if PARACHUTE == ENABLED
parachute.set_is_flying(!ap.land_complete);
#endif
AP_Notify::flags.flying = !ap.land_complete; AP_Notify::flags.flying = !ap.land_complete;
} }

View File

@ -178,6 +178,12 @@ void Copter::parachute_check()
return; return;
} }
// pass is_flying to parachute library
parachute.set_is_flying(!ap.land_complete);
// pass sink rate to parachute library
parachute.set_sink_rate(-inertial_nav.get_velocity_z() * 0.01f);
// exit immediately if in standby // exit immediately if in standby
if (standby_active) { if (standby_active) {
return; return;
@ -214,8 +220,8 @@ void Copter::parachute_check()
return; return;
} }
// pass sink rate to parachute library // trigger parachute release based on sink rate
parachute.set_sink_rate(-inertial_nav.get_velocity_z() * 0.01); parachute.check_sink_rate();
// check for angle error over 30 degrees // check for angle error over 30 degrees
const float angle_error = attitude_control->get_att_error_angle_deg(); const float angle_error = attitude_control->get_att_error_angle_deg();