Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: Emergency Parachute Feature #9506

Merged
merged 5 commits into from
Apr 30, 2019

Conversation

viniciusknabben
Copy link
Contributor

  • Releases parachute if a maximum vertical speed is reached

  • Releases parachute if a minumum battery voltage is reached

  • Created parameter to enable emergency parachute

  • Created parameters to set up emergency threshold values

Signed-off-by: Vinicius Knabben viniciusknabben@hotmail.com

@OXINARF
Copy link
Member

OXINARF commented Oct 3, 2018

Hi @viniciusknabben, thank you for your first contribution and welcome to ArduPilot! Please read our contribution rules at http://ardupilot.org/dev/docs/submitting-patches-back-to-master.html, especially the parts about the commit message rules and the commit per-library/vehicle.

ArduPlane/parachute.cpp Outdated Show resolved Hide resolved
@viniciusknabben
Copy link
Contributor Author

Should i rename the PR to Plane: Emergency Parachute Feature ?

gcs().send_text(MAV_SEVERITY_CRITICAL,"Emergency Parachute: Stall detected");
parachute_release();
}
else if (battery.voltage() < parachute.min_batt_voltage()) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This batt check needs hysteresis. Battery is notoriously noisy and fluctuates a lot depending on throttle and you don't want a single check to trigger the parachute. Perhaps what we need is a "super low-pass" version in the battery library because doing checks like are not the parachute's library duty to deal with.

Copy link
Contributor Author

@viniciusknabben viniciusknabben Oct 3, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Agreed, I will make a deep read on AP_BattMonitor and work on it

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'll take care of the battery stuff right now

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Here's a PR #9508

please give it a try on your branch

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Cool, i will do it

@magicrub
Copy link
Contributor

magicrub commented Oct 3, 2018

These are generic checks that should get moved into AP_Parachute. Both copter and plane would benefit from:

  • battery
  • !flying
  • sink rate

They should all be in the single parachute::update()
A good general goal is copter and plane should share as much code as possible through the libraries.

The easiest way to do this is to add accessors in the chute library for an isFlying flag because those are determined by different mechanisms in plave vs copter. For plane, just pass it the is_flying flag when it gets set in is_flying.cpp like how frsky and adsb does.
https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/is_flying.cpp#L149

Same with sink rate, although I think we could be smarter with that through ahrs singleton but for now simply passing it the auto_state.sink_rate is fine.

Copy link
Contributor

@WickedShell WickedShell left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The battery one is actually much easier to handle. Unless there is a strong reason not to, you should simply be adding release parachute as a battery failsafe action. The battery library will manage the triggers for you, add the time requirement, and will allow you to trigger off of capacity as well. All you have to do to make this work is add it to the list of enums (and priorities) here https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/Plane.h#L1043

Then handle the action here: https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/events.cpp#L143 (this would just be calling parachute_release())

@viniciusknabben viniciusknabben changed the title AP - Added Emergency Parachute Feature AP_Emergency Parachute Feature Oct 4, 2018
@viniciusknabben viniciusknabben changed the title AP_Emergency Parachute Feature Plane: Emergency Parachute Feature Oct 4, 2018
@viniciusknabben
Copy link
Contributor Author

@WickedShell @magicrub , code updated

ArduPlane/Plane.h Outdated Show resolved Hide resolved
ArduPlane/events.cpp Outdated Show resolved Hide resolved
@@ -20,6 +20,10 @@

#define AP_PARACHUTE_ALT_MIN_DEFAULT 10 // default min altitude the vehicle should have before parachute is released

#define AP_PARACHUTE_EMERGENCY_DEFAULT 0 // default value to emergency parachute
#define AP_PARACHUTE_MAX_SINK_DEFAULT 10.0 // default maximun sink speed in m/s to trigger emergency parachute
#define AP_PARACHUTE_MIN_BATT_VOLTAGE_DEFAULT 10.0 // default minimum battery voltage to trigger emergency parachute
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is unneeded now that you are leveraging the failsafe system.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We should keep emergency and max sink default values, i will remove battery for now.

libraries/AP_Parachute/AP_Parachute.h Outdated Show resolved Hide resolved
libraries/AP_Parachute/AP_Parachute.cpp Outdated Show resolved Hide resolved
@viniciusknabben
Copy link
Contributor Author

@WickedShell

@viniciusknabben
Copy link
Contributor Author

@tridge @WickedShell

1 similar comment
@viniciusknabben
Copy link
Contributor Author

@tridge @WickedShell

@viniciusknabben viniciusknabben force-pushed the emergency_parachute branch 3 times, most recently from 4df17f9 to cc80551 Compare February 11, 2019 14:24
tridge
tridge previously requested changes Feb 12, 2019
void set_is_flying(const bool is_flying) { _is_flying = is_flying; }

// get_sink_rate - gets vehicle sink rate
void get_sink_rate(float sink_rate) { _sink_rate = sink_rate; }
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this should be set_sink_rate() not get_sink_rate()

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Right

libraries/AP_Parachute/AP_Parachute.cpp Outdated Show resolved Hide resolved
@tridge
Copy link
Contributor

tridge commented Feb 19, 2019

i think this looks good now, except for minor things:

  • the commit msg for plane makes no sense for the change
  • copter should call set_sink_rate() so it works on copters (as its a common parameter)

@tridge
Copy link
Contributor

tridge commented Feb 19, 2019

if you don't know how to fix commit msgs (and squash commits) then let me know and I can do it for you

@viniciusknabben
Copy link
Contributor Author

if you don't know how to fix commit msgs (and squash commits) then let me know and I can do it for you

git rebase -i HEAD~x right? then squash and and change commit msg.

can you explain me about the commit msg? should i squash all commits into a single one and write a msg like: Plane: Added parachute release for dangerous sinking and battery failsafe

@viniciusknabben
Copy link
Contributor Author

* copter should call set_sink_rate() so it works on copters (as its a common parameter)

I'm a bit confused where copter calcs its altitude variation to call set_sink_rate()

@peterbarker
Copy link
Contributor

peterbarker commented Feb 20, 2019 via email

@viniciusknabben viniciusknabben force-pushed the emergency_parachute branch 2 times, most recently from f7ffcc8 to bca10cb Compare February 21, 2019 13:06
@tridge
Copy link
Contributor

tridge commented Feb 21, 2019

I've added in the sink rate to copter.
When adding it though I wondered about temporary glitches in sink rate estimation. Perhaps we should make this check in the parachute library require that the sink rate be exceeded continuously for a full second?

@viniciusknabben
Copy link
Contributor Author

I've added in the sink rate to copter.
When adding it though I wondered about temporary glitches in sink rate estimation. Perhaps we should make this check in the parachute library require that the sink rate be exceeded continuously for a full second?

Agreed, we could also make this a parameter.

In some cases the plane/copter could have time to recover, the user change the value

@peterbarker
Copy link
Contributor

Rebase required.

Last commit needs fixup'ing into another.

@viniciusknabben viniciusknabben force-pushed the emergency_parachute branch 2 times, most recently from b5e0d6b to f6e1b6b Compare March 27, 2019 11:51
@viniciusknabben
Copy link
Contributor Author

@peterbarker Rebase done

@peterbarker
Copy link
Contributor

@viniciusknabben Do you think you have addressed @WickedShell 's concerns in his review?

@viniciusknabben
Copy link
Contributor Author

viniciusknabben commented Mar 28, 2019

@peterbarker, i think i did, the concern was about where to handle the parachute release when the battery reaches a critical voltage. The triggers were already there and i simply added the parachute action (3bdf81b and 9b2611d) as suggested by @WickedShell.

@@ -172,6 +172,10 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
afs.gcs_terminate(true, battery_type_str);
break;

case Failsafe_Action_Parachute:
parachute_release();
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should the vehicle be disarmed here? I haven't investigated the parachute code in the past, but what keeps us from spinning motors once the parachute has been released?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The throttle is suppressed when the parachute release is initiated.

bool Plane::suppress_throttle(void)
{
#if PARACHUTE == ENABLED
if (auto_throttle_mode && parachute.release_initiated()) {
// throttle always suppressed in auto-throttle modes after parachute release initiated
throttle_suppressed = true;
return true;
}
#endif

@peterbarker
Copy link
Contributor

This needs a rebase. There's a regression test for it here: https://github.com/peterbarker/ardupilot/tree/emergency_parachute - it would be nice to cherry-pick that on top.

viniciusknabben and others added 5 commits April 29, 2019 10:19
…afe actions

Signed-off-by: Vinicius Knabben <viniciusknabben@hotmail.com>
The user can now set the parachute release as a failsafe action

Signed-off-by: Vinicius Knabben <viniciusknabben@hotmail.com>
Signed-off-by: Vinicius Knabben <viniciusknabben@hotmail.com>
Signed-off-by: Vinicius Knabben <viniciusknabben@hotmail.com>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

7 participants