|
|
@ -28,21 +28,21 @@ void Sub::init_rc_in() |
|
|
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL |
|
|
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL |
|
|
|
// initialize rc input to 1500 on control channels (rather than 0)
|
|
|
|
// initialize rc input to 1500 on control channels (rather than 0)
|
|
|
|
for (int i = 0; i < 6; i++) { |
|
|
|
for (int i = 0; i < 6; i++) { |
|
|
|
hal.rcin->set_override(i, 1500); |
|
|
|
RC_Channels::set_override(i, 1500); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
hal.rcin->set_override(6, 1500); // camera pan channel
|
|
|
|
RC_Channels::set_override(6, 1500); // camera pan channel
|
|
|
|
hal.rcin->set_override(7, 1500); // camera tilt channel
|
|
|
|
RC_Channels::set_override(7, 1500); // camera tilt channel
|
|
|
|
|
|
|
|
|
|
|
|
RC_Channel* chan = RC_Channels::rc_channel(8); |
|
|
|
RC_Channel* chan = RC_Channels::rc_channel(8); |
|
|
|
uint16_t min = chan->get_radio_min(); |
|
|
|
uint16_t min = chan->get_radio_min(); |
|
|
|
hal.rcin->set_override(8, min); // lights 1 channel
|
|
|
|
RC_Channels::set_override(8, min); // lights 1 channel
|
|
|
|
|
|
|
|
|
|
|
|
chan = RC_Channels::rc_channel(9); |
|
|
|
chan = RC_Channels::rc_channel(9); |
|
|
|
min = chan->get_radio_min(); |
|
|
|
min = chan->get_radio_min(); |
|
|
|
hal.rcin->set_override(9, min); // lights 2 channel
|
|
|
|
RC_Channels::set_override(9, min); // lights 2 channel
|
|
|
|
|
|
|
|
|
|
|
|
hal.rcin->set_override(10, 1100); // video switch
|
|
|
|
RC_Channels::set_override(10, 1100); // video switch
|
|
|
|
#endif |
|
|
|
#endif |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|