Rover: Use RC_Channels instead of hal.rcin

This commit is contained in:
Michael du Breuil 2018-04-03 19:17:20 -07:00 committed by Francisco Ferreira
parent 3e4288d604
commit 05173f24c6
5 changed files with 13 additions and 22 deletions

View File

@ -948,19 +948,16 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
}
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);
rover.failsafe.rc_override_timer = AP_HAL::millis();
rover.failsafe_trigger(FAILSAFE_EVENT_RC, false);
@ -982,8 +979,8 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
const int16_t roll = (packet.y == INT16_MAX) ? 0 : rover.channel_steer->get_radio_min() + (rover.channel_steer->get_radio_max() - rover.channel_steer->get_radio_min()) * (packet.y + 1000) / 2000.0f;
const int16_t throttle = (packet.z == INT16_MAX) ? 0 : rover.channel_throttle->get_radio_min() + (rover.channel_throttle->get_radio_max() - rover.channel_throttle->get_radio_min()) * (packet.z + 1000) / 2000.0f;
hal.rcin->set_override(uint8_t(rover.rcmap.roll() - 1), roll);
hal.rcin->set_override(uint8_t(rover.rcmap.throttle() - 1), throttle);
RC_Channels::set_override(uint8_t(rover.rcmap.roll() - 1), roll);
RC_Channels::set_override(uint8_t(rover.rcmap.throttle() - 1), throttle);
rover.failsafe.rc_override_timer = AP_HAL::millis();
rover.failsafe_trigger(FAILSAFE_EVENT_RC, false);

View File

@ -241,10 +241,6 @@ private:
// This is set to -1 when we need to re-read the switch
uint8_t oldSwitchPosition;
// These are values received from the GCS if the user is using GCS joystick
// control and are substituted for the values coming from the RC radio
int16_t rc_override[8];
// A flag if GCS joystick control is in use
bool rc_override_active;

View File

@ -63,7 +63,7 @@ void Rover::read_control_switch()
// as a spring loaded trainer switch).
if (oldSwitchPosition != switchPosition ||
(g.reset_switch_chan != 0 &&
hal.rcin->read(g.reset_switch_chan-1) > RESET_SWITCH_CHAN_PWM)) {
RC_Channels::get_radio_in(g.reset_switch_chan-1) > RESET_SWITCH_CHAN_PWM)) {
if (switch_debouncer == false) {
// this ensures that mode switches only happen if the
// switch changes for 2 reads. This prevents momentary
@ -85,7 +85,7 @@ void Rover::read_control_switch()
}
uint8_t Rover::readSwitch(void) {
const uint16_t pulsewidth = hal.rcin->read(g.mode_channel - 1);
const uint16_t pulsewidth = RC_Channels::get_radio_in(g.mode_channel - 1);
if (pulsewidth <= 900 || pulsewidth >= 2200) {
return 255; // This is an error condition
}

View File

@ -101,7 +101,7 @@ void Rover::rudder_arm_disarm_check()
void Rover::read_radio()
{
if (!hal.rcin->new_input()) {
if (!RC_Channels::has_new_input()) {
// check if we lost RC link
control_failsafe(channel_throttle->get_radio_in());
return;

View File

@ -109,8 +109,6 @@ void Rover::init_ardupilot()
gps.set_log_gps_bit(MASK_LOG_GPS);
gps.init(serial_manager);
rc_override_active = hal.rcin->set_overrides(rc_override, 8);
ins.set_log_raw_bit(MASK_LOG_IMU_RAW);
set_control_channels(); // setup radio channels and ouputs ranges