mirror of https://github.com/ArduPilot/ardupilot
AP_Parachute: adapt to new RC_Channel API
This commit is contained in:
parent
4173432542
commit
7706741b9b
|
@ -2,6 +2,7 @@
|
|||
#include <AP_Relay/AP_Relay.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <RC_Channel/RC_Channel.h>
|
||||
#include <SRV_Channel/SRV_Channel.h>
|
||||
#include <AP_Notify/AP_Notify.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
|
@ -107,7 +108,7 @@ void AP_Parachute::update()
|
|||
if (time_diff >= delay_ms) {
|
||||
if (_release_type == AP_PARACHUTE_TRIGGER_TYPE_SERVO) {
|
||||
// move servo
|
||||
RC_Channel_aux::set_radio(RC_Channel_aux::k_parachute_release, _servo_on_pwm);
|
||||
SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_on_pwm);
|
||||
}else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
|
||||
// set relay
|
||||
_relay.on(_release_type);
|
||||
|
@ -118,7 +119,7 @@ void AP_Parachute::update()
|
|||
}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
|
||||
RC_Channel_aux::set_radio(RC_Channel_aux::k_parachute_release, _servo_off_pwm);
|
||||
SRV_Channels::set_output_pwm(SRV_Channel::k_parachute_release, _servo_off_pwm);
|
||||
}else if (_release_type <= AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) {
|
||||
// set relay back to zero volts
|
||||
_relay.off(_release_type);
|
||||
|
|
Loading…
Reference in New Issue