AP_Parachute: Add function to return _release_in_progress status

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2017-07-26 09:29:00 -03:00 committed by Francisco Ferreira
parent 572df8b859
commit 1eeea82e31

View File

@ -52,6 +52,9 @@ public:
/// release_initiated - true if the parachute release sequence has been initiated (may wait before actual release) /// release_initiated - true if the parachute release sequence has been initiated (may wait before actual release)
bool release_initiated() const { return _release_initiated; } bool release_initiated() const { return _release_initiated; }
/// release_in_progress - true if the parachute release sequence is in progress
bool release_in_progress() const { return _release_in_progress; }
/// 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();