Sub: Use RC_Channels instead of hal.rcin

This commit is contained in:
Michael du Breuil 2018-04-03 19:17:57 -07:00 committed by Francisco Ferreira
parent d96919ed21
commit 9f673c2746
3 changed files with 16 additions and 19 deletions

View File

@ -949,19 +949,16 @@ void GCS_MAVLINK_Sub::handleMessage(mavlink_message_t* msg)
break; // Only accept control from our gcs
}
mavlink_rc_channels_override_t packet;
int16_t v[8];
mavlink_msg_rc_channels_override_decode(msg, &packet);
v[0] = packet.chan1_raw;
v[1] = packet.chan2_raw;
v[2] = packet.chan3_raw;
v[3] = packet.chan4_raw;
v[4] = packet.chan5_raw;
v[5] = packet.chan6_raw;
v[6] = packet.chan7_raw;
v[7] = packet.chan8_raw;
hal.rcin->set_overrides(v, 8);
RC_Channels::set_override(0, packet.chan1_raw);
RC_Channels::set_override(1, packet.chan2_raw);
RC_Channels::set_override(2, packet.chan3_raw);
RC_Channels::set_override(3, packet.chan4_raw);
RC_Channels::set_override(4, packet.chan5_raw);
RC_Channels::set_override(5, packet.chan6_raw);
RC_Channels::set_override(6, packet.chan7_raw);
RC_Channels::set_override(7, packet.chan8_raw);
sub.failsafe.last_pilot_input_ms = AP_HAL::millis();
// a RC override message is considered to be a 'heartbeat' from the ground station for failsafe purposes

View File

@ -121,7 +121,7 @@ void Sub::transform_manual_control_to_rc_override(int16_t x, int16_t y, int16_t
y_last = y;
z_last = z;
hal.rcin->set_overrides(channels, 11);
RC_Channels::set_overrides(channels, 11);
}
void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
@ -690,7 +690,7 @@ void Sub::set_neutral_controls()
channels[i] = 0xffff;
}
hal.rcin->set_overrides(channels, 10);
RC_Channels::set_overrides(channels, 10);
// Clear pitch/roll trim settings
pitchTrim = 0;

View File

@ -28,21 +28,21 @@ void Sub::init_rc_in()
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
// initialize rc input to 1500 on control channels (rather than 0)
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
hal.rcin->set_override(7, 1500); // camera tilt channel
RC_Channels::set_override(6, 1500); // camera pan channel
RC_Channels::set_override(7, 1500); // camera tilt channel
RC_Channel* chan = RC_Channels::rc_channel(8);
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);
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
}