diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index a4a6b8de2e..b3fd1990ec 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -150,7 +150,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #endif SCHED_TASK_CLASS(AP_InertialSensor, &copter.ins, periodic, 400, 50), SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75), - SCHED_TASK(read_receiver_rssi, 10, 75), #if RPM_ENABLED == ENABLED SCHED_TASK(rpm_update, 10, 200), #endif diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 662a755eb7..a2cb195116 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -378,9 +378,6 @@ private: AP_BoardConfig_CAN BoardConfig_CAN; #endif - // receiver RSSI - uint8_t receiver_rssi; - // Failsafe struct { uint32_t last_heartbeat_ms; // the time when the last HEARTBEAT message arrived from a GCS - used for triggering gcs failsafe @@ -886,7 +883,6 @@ private: void compass_accumulate(void); void init_optflow(); void update_optical_flow(void); - void read_receiver_rssi(void); void compass_cal_update(void); void accel_cal_update(void); void init_proximity(); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 3cb61e95b4..96e753817f 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -334,11 +334,6 @@ bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id) copter.send_nav_controller_output(chan); break; - case MSG_RADIO_IN: - CHECK_PAYLOAD_SIZE(RC_CHANNELS); - send_radio_in(copter.receiver_rssi); - break; - case MSG_SERVO_OUTPUT_RAW: CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW); send_servo_output_raw(false); diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index b769456258..c69862512f 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -162,13 +162,6 @@ void Copter::update_optical_flow(void) } #endif // OPTFLOW == ENABLED -// read the receiver RSSI as an 8 bit number for MAVLink -// RC_CHANNELS_SCALED message -void Copter::read_receiver_rssi(void) -{ - receiver_rssi = rssi.read_receiver_rssi_uint8(); -} - void Copter::compass_cal_update() { static uint32_t compass_cal_stick_gesture_begin = 0;