mirror of https://github.com/ArduPilot/ardupilot
AP_Parachute: add option to disable relay and servorelay libraries
This commit is contained in:
parent
e423173848
commit
2adb4fef5a
|
@ -137,12 +137,14 @@ void AP_Parachute::update()
|
|||
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
||||
// move servo
|
||||
SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_on_pwm);
|
||||
#if AP_RELAY_ENABLED
|
||||
} else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
|
||||
// set relay
|
||||
AP_Relay*_relay = AP::relay();
|
||||
if (_relay != nullptr) {
|
||||
_relay->on(_release_type);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
_release_in_progress = true;
|
||||
_released = true;
|
||||
|
@ -152,12 +154,14 @@ void AP_Parachute::update()
|
|||
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
||||
// move servo back to off position
|
||||
SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_off_pwm);
|
||||
#if AP_RELAY_ENABLED
|
||||
} else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
|
||||
// set relay back to zero volts
|
||||
AP_Relay*_relay = AP::relay();
|
||||
if (_relay != nullptr) {
|
||||
_relay->off(_release_type);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
// reset released flag and release_time
|
||||
_release_in_progress = false;
|
||||
|
@ -212,12 +216,17 @@ bool AP_Parachute::arming_checks(size_t buflen, char *buffer) const
|
|||
return false;
|
||||
}
|
||||
} else {
|
||||
#if AP_RELAY_ENABLED
|
||||
AP_Relay*_relay = AP::relay();
|
||||
if (_relay == nullptr || !_relay->enabled(_release_type)) {
|
||||
hal.util->snprintf(buffer, buflen, "Chute invalid relay %d", int(_release_type));
|
||||
return false;
|
||||
}
|
||||
#else
|
||||
hal.util->snprintf(buffer, buflen, "AP_Relay not available");
|
||||
#endif
|
||||
}
|
||||
|
||||
if (_release_initiated) {
|
||||
hal.util->snprintf(buffer, buflen, "Chute is released");
|
||||
return false;
|
||||
|
|
Loading…
Reference in New Issue