mirror of https://github.com/ArduPilot/ardupilot
AP_Parachute: added arming_checks()
This commit is contained in:
parent
09ad43dea3
commit
8660e98b57
|
@ -187,6 +187,23 @@ void AP_Parachute::check_sink_rate()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check settings are valid
|
||||||
|
bool AP_Parachute::arming_checks(size_t buflen, char *buffer) const
|
||||||
|
{
|
||||||
|
if (_enabled > 0) {
|
||||||
|
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
||||||
|
if (!SRV_Channels::function_assigned(SRV_Channel::k_parachute_release)) {
|
||||||
|
hal.util->snprintf(buffer, buflen, "Chute has no channel");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
} else if (!_relay.enabled(_release_type)) {
|
||||||
|
hal.util->snprintf(buffer, buflen, "Chute invalid relay %d", _release_type);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
// singleton instance
|
// singleton instance
|
||||||
AP_Parachute *AP_Parachute::_singleton;
|
AP_Parachute *AP_Parachute::_singleton;
|
||||||
|
|
||||||
|
|
|
@ -86,6 +86,9 @@ public:
|
||||||
// trigger parachute release if sink_rate is below critical_sink_rate for 1sec
|
// trigger parachute release if sink_rate is below critical_sink_rate for 1sec
|
||||||
void check_sink_rate();
|
void check_sink_rate();
|
||||||
|
|
||||||
|
// check settings are valid
|
||||||
|
bool arming_checks(size_t buflen, char *buffer) const;
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
// get singleton instance
|
// get singleton instance
|
||||||
|
|
Loading…
Reference in New Issue