Plane: use RC_Channel::rc_channel() instead of rc_ch[]

This commit is contained in:
Andrew Tridgell 2013-06-03 15:11:55 +10:00
parent 9076f6a1d0
commit 515d726ee0
4 changed files with 10 additions and 24 deletions

View File

@ -340,19 +340,18 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan)
{
#if HIL_MODE != HIL_MODE_DISABLED
if (!g.hil_servos) {
extern RC_Channel* rc_ch[8];
mavlink_msg_servo_output_raw_send(
chan,
micros(),
0, // port
rc_ch[0]->radio_out,
rc_ch[1]->radio_out,
rc_ch[2]->radio_out,
rc_ch[3]->radio_out,
rc_ch[4]->radio_out,
rc_ch[5]->radio_out,
rc_ch[6]->radio_out,
rc_ch[7]->radio_out);
RC_Channel::rc_channel(0)->radio_out,
RC_Channel::rc_channel(1)->radio_out,
RC_Channel::rc_channel(2)->radio_out,
RC_Channel::rc_channel(3)->radio_out,
RC_Channel::rc_channel(4)->radio_out,
RC_Channel::rc_channel(5)->radio_out,
RC_Channel::rc_channel(6)->radio_out,
RC_Channel::rc_channel(7)->radio_out);
return;
}
#endif

View File

@ -626,7 +626,6 @@ static void do_set_relay()
static void do_repeat_servo(uint8_t channel, uint16_t servo_value,
int16_t repeat, uint8_t delay_time)
{
extern RC_Channel *rc_ch[8];
channel = channel - 1;
if (channel < 5 || channel > 8) {
// not allowed
@ -639,7 +638,7 @@ static void do_repeat_servo(uint8_t channel, uint16_t servo_value,
event_state.delay_ms = delay_time * 500UL;
event_state.repeat = repeat * 2;
event_state.servo_value = servo_value;
event_state.undo_value = rc_ch[channel]->radio_trim;
event_state.undo_value = RC_Channel::rc_channel(channel)->radio_trim;
update_events();
}

View File

@ -5,8 +5,6 @@
static uint8_t failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
extern RC_Channel* rc_ch[8];
static void init_rc_in()
{
// set rc channel ranges
@ -26,15 +24,6 @@ static void init_rc_in()
//g.channel_rudder.dead_zone = 60;
//g.channel_throttle.dead_zone = 6;
rc_ch[CH_1] = &g.channel_roll;
rc_ch[CH_2] = &g.channel_pitch;
rc_ch[CH_3] = &g.channel_throttle;
rc_ch[CH_4] = &g.channel_rudder;
rc_ch[CH_5] = &g.rc_5;
rc_ch[CH_6] = &g.rc_6;
rc_ch[CH_7] = &g.rc_7;
rc_ch[CH_8] = &g.rc_8;
//set auxiliary ranges
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11, &g.rc_12);

View File

@ -645,9 +645,8 @@ static void servo_write(uint8_t ch, uint16_t pwm)
{
#if HIL_MODE != HIL_MODE_DISABLED
if (!g.hil_servos) {
extern RC_Channel *rc_ch[8];
if (ch < 8) {
rc_ch[ch]->radio_out = pwm;
RC_Channel::rc_channel(ch)->radio_out = pwm;
}
return;
}