Plane: Use RC_Channels instead of hal.rcin

This commit is contained in:
Michael du Breuil 2018-04-03 19:17:05 -07:00 committed by Francisco Ferreira
parent a6afc69c13
commit 3e4288d604
8 changed files with 27 additions and 27 deletions

View File

@ -649,7 +649,7 @@ void Plane::update_flight_mode(void)
}
if (g.fbwa_tdrag_chan > 0) {
// check for the user enabling FBWA taildrag takeoff mode
bool tdrag_mode = (hal.rcin->read(g.fbwa_tdrag_chan-1) > 1700);
bool tdrag_mode = (RC_Channels::get_radio_in(g.fbwa_tdrag_chan-1) > 1700);
if (tdrag_mode && !auto_state.fbwa_tdrag_takeoff_mode) {
if (auto_state.highest_airspeed < g.takeoff_tdrag_speed1) {
auto_state.fbwa_tdrag_takeoff_mode = true;

View File

@ -1393,19 +1393,19 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
// and RC PWM values.
if(msg->sysid != plane.g.sysid_my_gcs) break; // Only accept control from our gcs
mavlink_rc_channels_override_t packet;
int16_t v[8];
bool override_active = false;
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;
override_active |= RC_Channels::set_override(0, packet.chan1_raw);
override_active |= RC_Channels::set_override(1, packet.chan2_raw);
override_active |= RC_Channels::set_override(2, packet.chan3_raw);
override_active |= RC_Channels::set_override(3, packet.chan4_raw);
override_active |= RC_Channels::set_override(4, packet.chan5_raw);
override_active |= RC_Channels::set_override(5, packet.chan6_raw);
override_active |= RC_Channels::set_override(6, packet.chan7_raw);
override_active |= RC_Channels::set_override(7, packet.chan8_raw);
if (hal.rcin->set_overrides(v, 8)) {
if (override_active) {
plane.failsafe.last_valid_rc_ms = AP_HAL::millis();
plane.failsafe.AFS_last_valid_rc_ms = plane.failsafe.last_valid_rc_ms;
}
@ -1435,10 +1435,10 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
int16_t throttle = (packet.z == INT16_MAX) ? 0 : plane.channel_throttle->get_radio_min() + (plane.channel_throttle->get_radio_max() - plane.channel_throttle->get_radio_min()) * (packet.z) / 1000.0f;
int16_t yaw = (packet.r == INT16_MAX) ? 0 : plane.channel_rudder->get_radio_min() + (plane.channel_rudder->get_radio_max() - plane.channel_rudder->get_radio_min()) * (packet.r + 1000) / 2000.0f;
override_active |= hal.rcin->set_override(uint8_t(plane.rcmap.roll() - 1), roll);
override_active |= hal.rcin->set_override(uint8_t(plane.rcmap.pitch() - 1), pitch);
override_active |= hal.rcin->set_override(uint8_t(plane.rcmap.throttle() - 1), throttle);
override_active |= hal.rcin->set_override(uint8_t(plane.rcmap.yaw() - 1), yaw);
override_active |= RC_Channels::set_override(uint8_t(plane.rcmap.roll() - 1), roll);
override_active |= RC_Channels::set_override(uint8_t(plane.rcmap.pitch() - 1), pitch);
override_active |= RC_Channels::set_override(uint8_t(plane.rcmap.throttle() - 1), throttle);
override_active |= RC_Channels::set_override(uint8_t(plane.rcmap.yaw() - 1), yaw);
if (override_active) {
plane.failsafe.last_valid_rc_ms = AP_HAL::millis();

View File

@ -28,7 +28,7 @@ void Plane::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
@ -45,7 +45,7 @@ void Plane::read_control_switch()
}
if (g.reset_mission_chan != 0 &&
hal.rcin->read(g.reset_mission_chan-1) > RESET_SWITCH_CHAN_PWM) {
RC_Channels::get_radio_in(g.reset_mission_chan-1) > RESET_SWITCH_CHAN_PWM) {
mission.start();
prev_WP_loc = current_loc;
}
@ -55,12 +55,12 @@ void Plane::read_control_switch()
if (g.inverted_flight_ch != 0) {
// if the user has configured an inverted flight channel, then
// fly upside down when that channel goes above INVERTED_FLIGHT_PWM
inverted_flight = (control_mode != MANUAL && hal.rcin->read(g.inverted_flight_ch-1) > INVERTED_FLIGHT_PWM);
inverted_flight = (control_mode != MANUAL && RC_Channels::get_radio_in(g.inverted_flight_ch-1) > INVERTED_FLIGHT_PWM);
}
#if PARACHUTE == ENABLED
if (g.parachute_channel > 0) {
if (hal.rcin->read(g.parachute_channel-1) >= 1700) {
if (RC_Channels::get_radio_in(g.parachute_channel-1) >= 1700) {
parachute_manual_release();
}
}
@ -69,7 +69,7 @@ void Plane::read_control_switch()
#if HAVE_PX4_MIXER
if (g.override_channel > 0) {
// if the user has configured an override channel then check it
bool override_requested = (hal.rcin->read(g.override_channel-1) >= PX4IO_OVERRIDE_PWM);
bool override_requested = (RC_Channels::get_radio_in(g.override_channel-1) >= PX4IO_OVERRIDE_PWM);
if (override_requested && !px4io_override_enabled) {
if (hal.util->get_soft_armed() || (last_mixer_crc != -1)) {
px4io_override_enabled = true;
@ -100,7 +100,7 @@ void Plane::read_control_switch()
uint8_t Plane::readSwitch(void)
{
uint16_t pulsewidth = hal.rcin->read(g.flight_mode_channel - 1);
uint16_t pulsewidth = RC_Channels::get_radio_in(g.flight_mode_channel - 1);
if (pulsewidth <= 900 || pulsewidth >= 2200) return 255; // This is an error condition
if (pulsewidth <= 1230) return 0;
if (pulsewidth <= 1360) return 1;

View File

@ -63,7 +63,7 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, mode_reason_t rea
// This is how to handle a long loss of control signal failsafe.
gcs().send_text(MAV_SEVERITY_WARNING, "Failsafe. Long event on: type=%u/reason=%u", fstype, reason);
// If the GCS is locked up we allow control to revert to RC
hal.rcin->clear_overrides();
RC_Channels::clear_overrides();
failsafe.state = fstype;
switch(control_mode)
{

View File

@ -47,13 +47,13 @@ void Plane::failsafe_check(void)
afs.heartbeat();
}
if (hal.rcin->num_channels() < 5) {
if (RC_Channels::get_valid_channel_count() < 5) {
// we don't have any RC input to pass through
return;
}
// pass RC inputs to outputs every 20ms
hal.rcin->clear_overrides();
RC_Channels::clear_overrides();
int16_t roll = channel_roll->get_control_in_zero_dz();
int16_t pitch = channel_pitch->get_control_in_zero_dz();

View File

@ -175,7 +175,7 @@ void Plane::geofence_update_pwm_enabled_state()
if (g.fence_channel == 0) {
is_pwm_enabled = false;
} else {
is_pwm_enabled = (hal.rcin->read(g.fence_channel-1) > FENCE_ENABLE_PWM);
is_pwm_enabled = (RC_Channels::get_radio_in(g.fence_channel-1) > FENCE_ENABLE_PWM);
}
if (is_pwm_enabled && geofence_state == nullptr) {
// we need to load the fence

View File

@ -171,7 +171,7 @@ void Plane::rudder_arm_disarm_check()
void Plane::read_radio()
{
if (!hal.rcin->new_input()) {
if (!RC_Channels::has_new_input()) {
control_failsafe();
return;
}

View File

@ -118,7 +118,7 @@ void QuadPlane::tailsitter_output(void)
if (tailsitter.input_mask_chan > 0 &&
tailsitter.input_mask > 0 &&
hal.rcin->read(tailsitter.input_mask_chan-1) > 1700) {
RC_Channels::get_radio_in(tailsitter.input_mask_chan-1) > 1700) {
// the user is learning to prop-hang
if (tailsitter.input_mask & TAILSITTER_MASK_AILERON) {
SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, plane.channel_roll->get_control_in_zero_dz());