diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 16cc8e2094..37f0c80981 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -123,7 +123,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK(full_rate_logging_loop,400, 100), SCHED_TASK(dataflash_periodic, 400, 300), SCHED_TASK(perf_update, 0.1, 75), - SCHED_TASK(read_receiver_rssi, 10, 75), SCHED_TASK(rpm_update, 10, 200), SCHED_TASK(compass_cal_update, 100, 100), SCHED_TASK(accel_cal_update, 10, 100), @@ -377,9 +376,6 @@ void Sub::ten_hz_logging_loop() } if (should_log(MASK_LOG_RCIN)) { DataFlash.Log_Write_RCIN(); - if (rssi.enabled()) { - DataFlash.Log_Write_RSSI(rssi); - } } if (should_log(MASK_LOG_RCOUT)) { DataFlash.Log_Write_RCOUT(); diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index ada14aadfe..86531b416d 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -986,10 +986,6 @@ const AP_Param::Info Sub::var_info[] = { // @Group: MIS_ // @Path: ../libraries/AP_Mission/AP_Mission.cpp GOBJECT(mission, "MIS_", AP_Mission), - - // @Group: RSSI_ - // @Path: ../libraries/AP_RSSI/AP_RSSI.cpp - GOBJECT(rssi, "RSSI_", AP_RSSI), #if RANGEFINDER_ENABLED == ENABLED // @Group: RNGFND diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index ae4aff0ebb..f341345b47 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -123,9 +123,6 @@ public: k_param_throw_motor_start, k_param_terrain_follow, // 94 k_param_avoid, - - // 97: RSSI - k_param_rssi = 97, // // 100: Inertial Nav diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index bf19c449f3..b72bd2c120 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -66,7 +66,6 @@ #include // Range finder library #include #include // Optical Flow library -#include // RSSI Library #include // Filter library #include // APM FIFO Buffer #include // APM relay @@ -257,9 +256,6 @@ private: // board specific config AP_BoardConfig BoardConfig; - // receiver RSSI - uint8_t receiver_rssi; - // Failsafe struct { uint8_t rc_override_active : 1; // 0 // true if rc control are overwritten by ground station @@ -477,9 +473,6 @@ private: AP_Rally rally; #endif - // RSSI - AP_RSSI rssi; - // terrain handling #if AP_TERRAIN_AVAILABLE && AC_TERRAIN AP_Terrain terrain; @@ -826,7 +819,6 @@ private: void init_optflow(); void update_optical_flow(void); void read_battery(void); - void read_receiver_rssi(void); void gripper_update(); void terrain_update(); void terrain_logging(); diff --git a/ArduSub/make.inc b/ArduSub/make.inc index 66040f0eb2..4192b98e06 100644 --- a/ArduSub/make.inc +++ b/ArduSub/make.inc @@ -29,7 +29,6 @@ LIBRARIES += RC_Channel LIBRARIES += AP_Motors LIBRARIES += AP_RangeFinder LIBRARIES += AP_OpticalFlow -LIBRARIES += AP_RSSI LIBRARIES += Filter LIBRARIES += AP_Buffer LIBRARIES += AP_Relay diff --git a/ArduSub/sensors.cpp b/ArduSub/sensors.cpp index 427df68eeb..0d2e9db9ef 100644 --- a/ArduSub/sensors.cpp +++ b/ArduSub/sensors.cpp @@ -180,13 +180,6 @@ void Sub::read_battery(void) } } -// read the receiver RSSI as an 8 bit number for MAVLink -// RC_CHANNELS_SCALED message -void Sub::read_receiver_rssi(void) -{ - receiver_rssi = rssi.read_receiver_rssi_uint8(); -} - void Sub::compass_cal_update() { if (!hal.util->get_soft_armed()) { diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index 47bba657fa..2fcd88d532 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -121,9 +121,6 @@ void Sub::init_ardupilot() // initialise battery monitor battery.init(); - - // Init RSSI - rssi.init(); barometer.init();