AP_Parachute: added a released() function
used to help with throttle suppression in plane
This commit is contained in:
parent
76871ef0cd
commit
0d9715cfe8
@ -91,7 +91,7 @@ void AP_Parachute::update()
|
|||||||
uint32_t time_diff = hal.scheduler->millis() - _release_time;
|
uint32_t time_diff = hal.scheduler->millis() - _release_time;
|
||||||
|
|
||||||
// check if we should release parachute
|
// check if we should release parachute
|
||||||
if ((_release_time != 0) && !_released) {
|
if ((_release_time != 0) && !_release_in_progress) {
|
||||||
if (time_diff >= AP_PARACHUTE_RELEASE_DELAY_MS) {
|
if (time_diff >= AP_PARACHUTE_RELEASE_DELAY_MS) {
|
||||||
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
||||||
// move servo
|
// move servo
|
||||||
@ -100,6 +100,7 @@ void AP_Parachute::update()
|
|||||||
// set relay
|
// set relay
|
||||||
_relay.on(_release_type);
|
_relay.on(_release_type);
|
||||||
}
|
}
|
||||||
|
_release_in_progress = true;
|
||||||
_released = true;
|
_released = true;
|
||||||
}
|
}
|
||||||
}else if ((_release_time == 0) || time_diff >= AP_PARACHUTE_RELEASE_DELAY_MS + AP_PARACHUTE_RELEASE_DURATION_MS) {
|
}else if ((_release_time == 0) || time_diff >= AP_PARACHUTE_RELEASE_DELAY_MS + AP_PARACHUTE_RELEASE_DURATION_MS) {
|
||||||
@ -111,7 +112,7 @@ void AP_Parachute::update()
|
|||||||
_relay.off(_release_type);
|
_relay.off(_release_type);
|
||||||
}
|
}
|
||||||
// reset released flag and release_time
|
// reset released flag and release_time
|
||||||
_released = false;
|
_release_in_progress = false;
|
||||||
_release_time = 0;
|
_release_time = 0;
|
||||||
// update AP_Notify
|
// update AP_Notify
|
||||||
AP_Notify::flags.parachute_release = 0;
|
AP_Notify::flags.parachute_release = 0;
|
||||||
|
@ -49,6 +49,9 @@ public:
|
|||||||
/// release - release parachute
|
/// release - release parachute
|
||||||
void release();
|
void release();
|
||||||
|
|
||||||
|
/// released - true if the parachute has been released (or release is in progress)
|
||||||
|
bool released() const { return _released; }
|
||||||
|
|
||||||
/// update - shuts off the trigger should be called at about 10hz
|
/// update - shuts off the trigger should be called at about 10hz
|
||||||
void update();
|
void update();
|
||||||
|
|
||||||
@ -69,7 +72,8 @@ private:
|
|||||||
// internal variables
|
// internal variables
|
||||||
AP_Relay &_relay; // pointer to relay object from the base class Relay. The subclasses could be AP_Relay_APM1 or AP_Relay_APM2
|
AP_Relay &_relay; // pointer to relay object from the base class Relay. The subclasses could be AP_Relay_APM1 or AP_Relay_APM2
|
||||||
uint32_t _release_time; // system time that parachute is ordered to be released (actual release will happen 0.5 seconds later)
|
uint32_t _release_time; // system time that parachute is ordered to be released (actual release will happen 0.5 seconds later)
|
||||||
bool _released; // true if the parachute has been released
|
bool _release_in_progress:1; // true if the parachute release is in progress
|
||||||
|
bool _released:1; // true if the parachute has been released
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* AP_PARACHUTE_H */
|
#endif /* AP_PARACHUTE_H */
|
||||||
|
Loading…
Reference in New Issue
Block a user