diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 6189b2d281..e718273703 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -142,7 +142,12 @@ void GCS_MAVLINK_Rover::send_servo_out() 0, 0, 0, - receiver_rssi()); +#if AP_RSSI_ENABLED + receiver_rssi() +#else + 255 +#endif + ); } int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const diff --git a/Rover/Log.cpp b/Rover/Log.cpp index 6a3edb0184..3490e2a703 100644 --- a/Rover/Log.cpp +++ b/Rover/Log.cpp @@ -237,9 +237,11 @@ void Rover::Log_Write_RC(void) { logger.Write_RCIN(); logger.Write_RCOUT(); +#if AP_RSSI_ENABLED if (rssi.enabled()) { logger.Write_RSSI(); } +#endif } void Rover::Log_Write_Vehicle_Startup_Messages() diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 49c1f9a0be..0c740105e5 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -358,9 +358,11 @@ const AP_Param::Info Rover::var_info[] = { // @Path: ../libraries/AP_Mission/AP_Mission.cpp GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission), +#if AP_RSSI_ENABLED // @Group: RSSI_ // @Path: ../libraries/AP_RSSI/AP_RSSI.cpp GOBJECT(rssi, "RSSI_", AP_RSSI), +#endif // @Group: NTF_ // @Path: ../libraries/AP_Notify/AP_Notify.cpp diff --git a/Rover/system.cpp b/Rover/system.cpp index 451df4614e..02b93ab644 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -18,7 +18,9 @@ void Rover::init_ardupilot() rpm_sensor.init(); #endif +#if AP_RSSI_ENABLED rssi.init(); +#endif g2.windvane.init(serial_manager);