ardupilot/ArduPlane/parachute.cpp

52 lines
1.2 KiB
C++
Raw Normal View History

#include "Plane.h"
/*
call parachute library update
*/
void Plane::parachute_check()
{
parachute.update();
}
/*
parachute_release - trigger the release of the parachute
*/
void Plane::parachute_release()
{
if (parachute.released()) {
return;
}
// send message to gcs and dataflash
gcs_send_text(MAV_SEVERITY_CRITICAL,"Parachute: Released");
// release parachute
parachute.release();
}
/*
parachute_manual_release - trigger the release of the parachute,
after performing some checks for pilot error checks if the vehicle
is landed
*/
bool Plane::parachute_manual_release()
{
// exit immediately if parachute is not enabled
if (!parachute.enabled() || parachute.released()) {
return false;
}
if (parachute.alt_min() > 0 && relative_ground_altitude(false) < parachute.alt_min() &&
auto_state.last_flying_ms > 0) {
// Allow manual ground tests by only checking if flying too low if we've taken off
2015-11-18 15:17:50 -04:00
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Parachute: Too low");
return false;
}
// if we get this far release parachute
parachute_release();
return true;
}