mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Parachute: Added time check for sink rate to avoid glitches
Signed-off-by: Vinicius Knabben <viniciusknabben@hotmail.com>
This commit is contained in:
parent
55dca5cda9
commit
040fa3e10a
@ -115,10 +115,19 @@ void AP_Parachute::update()
|
|||||||
if (_enabled <= 0) {
|
if (_enabled <= 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
// check if the plane is sinking too fast and release parachute
|
// check if the plane is sinking too fast for more than a second and release parachute
|
||||||
|
uint32_t time = AP_HAL::millis();
|
||||||
if((_critical_sink > 0) && (_sink_rate > _critical_sink) && !_release_initiated && _is_flying) {
|
if((_critical_sink > 0) && (_sink_rate > _critical_sink) && !_release_initiated && _is_flying) {
|
||||||
|
if(_sink_time == 0) {
|
||||||
|
_sink_time = AP_HAL::millis();
|
||||||
|
}
|
||||||
|
if((time - _sink_time) >= 1000) {
|
||||||
release();
|
release();
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
_sink_time = 0;
|
||||||
|
}
|
||||||
|
|
||||||
// calc time since release
|
// calc time since release
|
||||||
uint32_t time_diff = AP_HAL::millis() - _release_time;
|
uint32_t time_diff = AP_HAL::millis() - _release_time;
|
||||||
uint32_t delay_ms = _delay_ms<=0 ? 0: (uint32_t)_delay_ms;
|
uint32_t delay_ms = _delay_ms<=0 ? 0: (uint32_t)_delay_ms;
|
||||||
|
@ -103,6 +103,7 @@ private:
|
|||||||
bool _released:1; // true if the parachute has been released
|
bool _released:1; // true if the parachute has been released
|
||||||
bool _is_flying:1; // true if the vehicle is flying
|
bool _is_flying:1; // true if the vehicle is flying
|
||||||
float _sink_rate; // vehicle sink rate in m/s
|
float _sink_rate; // vehicle sink rate in m/s
|
||||||
|
uint32_t _sink_time; // time that the vehicle exceeded critical sink rate
|
||||||
};
|
};
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
|
Loading…
Reference in New Issue
Block a user