mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: use new channel output API
This commit is contained in:
parent
11f196318e
commit
3c33eb3f09
@ -959,23 +959,7 @@ static void set_servos(void)
|
||||
channel_pitch->output();
|
||||
channel_throttle->output();
|
||||
channel_rudder->output();
|
||||
// Route configurable aux. functions to their respective servos
|
||||
g.rc_5.output_ch(CH_5);
|
||||
g.rc_6.output_ch(CH_6);
|
||||
g.rc_7.output_ch(CH_7);
|
||||
g.rc_8.output_ch(CH_8);
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
g.rc_9.output_ch(CH_9);
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
g.rc_10.output_ch(CH_10);
|
||||
g.rc_11.output_ch(CH_11);
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
g.rc_12.output_ch(CH_12);
|
||||
g.rc_13.output_ch(CH_13);
|
||||
g.rc_14.output_ch(CH_14);
|
||||
#endif
|
||||
RC_Channel_aux::output_ch_all();
|
||||
}
|
||||
|
||||
static bool demoing_servos;
|
||||
|
@ -52,22 +52,7 @@ static void init_rc_out()
|
||||
RC_Channel_aux::enable_aux_servos();
|
||||
|
||||
// Initialization of servo outputs
|
||||
for (uint8_t i=0; i<8; i++) {
|
||||
RC_Channel::rc_channel(i)->output_trim();
|
||||
}
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
servo_write(CH_9, g.rc_9.radio_trim);
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
servo_write(CH_10, g.rc_10.radio_trim);
|
||||
servo_write(CH_11, g.rc_11.radio_trim);
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
servo_write(CH_12, g.rc_12.radio_trim);
|
||||
servo_write(CH_13, g.rc_13.radio_trim);
|
||||
servo_write(CH_14, g.rc_14.radio_trim);
|
||||
#endif
|
||||
RC_Channel::output_trim_all();
|
||||
|
||||
// setup PX4 to output the min throttle when safety off if arming
|
||||
// is setup for min on disarm
|
||||
@ -150,6 +135,8 @@ static void read_radio()
|
||||
pwm_roll = BOOL_TO_SIGN(g.reverse_elevons) * (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int16_t(elevon.ch2_temp - elevon.trim2) - BOOL_TO_SIGN(g.reverse_ch1_elevon) * int16_t(elevon.ch1_temp - elevon.trim1)) / 2 + 1500;
|
||||
pwm_pitch = (BOOL_TO_SIGN(g.reverse_ch2_elevon) * int16_t(elevon.ch2_temp - elevon.trim2) + BOOL_TO_SIGN(g.reverse_ch1_elevon) * int16_t(elevon.ch1_temp - elevon.trim1)) / 2 + 1500;
|
||||
}
|
||||
|
||||
RC_Channel::set_pwm_all();
|
||||
|
||||
if (control_mode == TRAINING) {
|
||||
// in training mode we don't want to use a deadzone, as we
|
||||
@ -161,15 +148,8 @@ static void read_radio()
|
||||
} else {
|
||||
channel_roll->set_pwm(pwm_roll);
|
||||
channel_pitch->set_pwm(pwm_pitch);
|
||||
channel_throttle->set_pwm(channel_throttle->read());
|
||||
channel_rudder->set_pwm(channel_rudder->read());
|
||||
}
|
||||
|
||||
g.rc_5.set_pwm(hal.rcin->read(CH_5));
|
||||
g.rc_6.set_pwm(hal.rcin->read(CH_6));
|
||||
g.rc_7.set_pwm(hal.rcin->read(CH_7));
|
||||
g.rc_8.set_pwm(hal.rcin->read(CH_8));
|
||||
|
||||
control_failsafe(channel_throttle->radio_in);
|
||||
|
||||
channel_throttle->servo_out = channel_throttle->control_in;
|
||||
|
Loading…
Reference in New Issue
Block a user