mirror of https://github.com/ArduPilot/ardupilot
AP_Parachute: formatting fixes
This commit is contained in:
parent
dbf6f6f4b1
commit
17d4e797fb
|
@ -134,25 +134,25 @@ void AP_Parachute::update()
|
|||
// calc time since release
|
||||
uint32_t time_diff = AP_HAL::millis() - _release_time;
|
||||
uint32_t delay_ms = _delay_ms<=0 ? 0: (uint32_t)_delay_ms;
|
||||
|
||||
|
||||
// check if we should release parachute
|
||||
if ((_release_time != 0) && !_release_in_progress) {
|
||||
if (time_diff >= delay_ms) {
|
||||
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
||||
// move servo
|
||||
SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_on_pwm);
|
||||
}else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
|
||||
} else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
|
||||
// set relay
|
||||
_relay.on(_release_type);
|
||||
}
|
||||
_release_in_progress = true;
|
||||
_released = true;
|
||||
}
|
||||
}else if ((_release_time == 0) || time_diff >= delay_ms + AP_PARACHUTE_RELEASE_DURATION_MS) {
|
||||
} else if ((_release_time == 0) || time_diff >= delay_ms + AP_PARACHUTE_RELEASE_DURATION_MS) {
|
||||
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);
|
||||
}else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
|
||||
} else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
|
||||
// set relay back to zero volts
|
||||
_relay.off(_release_type);
|
||||
}
|
||||
|
|
|
@ -63,13 +63,13 @@ public:
|
|||
|
||||
/// released - true if the parachute has been released (or release is in progress)
|
||||
bool released() const { return _released; }
|
||||
|
||||
|
||||
/// release_initiated - true if the parachute release sequence has been initiated (may wait before actual release)
|
||||
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
|
||||
void update();
|
||||
|
||||
|
|
Loading…
Reference in New Issue