From c0c0b8c976856c7e06b06efcf0e4c675d69c1356 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 22 Aug 2012 13:33:12 +1000 Subject: [PATCH] APM: added RECEIVER_RSSI_PIN option this allows for the receiver RSSI to be sent over MAVLink Thanks to Burt Green for the suggestion --- ArduPlane/ArduPlane.pde | 4 ++++ ArduPlane/GCS_Mavlink.pde | 3 +-- ArduPlane/config.h | 5 +++++ ArduPlane/sensors.pde | 15 +++++++++++++++ 4 files changed, 25 insertions(+), 2 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 0c078ae6f9..37c6012e24 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -280,6 +280,10 @@ AP_RangeFinder_MaxsonarXL sonar(&pitot_analog_source, &sonar_mode_filter); AP_RangeFinder_MaxsonarXL sonar(&pitot_analog_source, &sonar_mode_filter); #endif +#if RECEIVER_RSSI_PIN != -1 +AP_AnalogSource_Arduino RSSI_pin(RECEIVER_RSSI_PIN, 0.25); +#endif + AP_Relay relay; diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 2fe7b21e32..dddd6a5547 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -286,7 +286,6 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan) static void NOINLINE send_servo_out(mavlink_channel_t chan) { - const uint8_t rssi = 1; // normalized values scaled to -10000 to 10000 // This is used for HIL. Do not change without discussing with // HIL maintainers @@ -302,7 +301,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan) 0, 0, 0, - rssi); + receiver_rssi()); } static void NOINLINE send_radio_in(mavlink_channel_t chan) diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 8f520da743..525e30ef9e 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -115,6 +115,11 @@ #endif +// pin for receiver RSSI +#ifndef RECEIVER_RSSI_PIN +# define RECEIVER_RSSI_PIN -1 +#endif + ////////////////////////////////////////////////////////////////////////////// // IMU Selection // diff --git a/ArduPlane/sensors.pde b/ArduPlane/sensors.pde index 1d7ca777c4..c77b22ade6 100644 --- a/ArduPlane/sensors.pde +++ b/ArduPlane/sensors.pde @@ -55,3 +55,18 @@ static void read_battery(void) #endif } + +// return receiver RSSI as an 8 bit number for MAVLink +// RC_CHANNELS_SCALED message +uint8_t receiver_rssi(void) +{ +#if RECEIVER_RSSI_PIN != -1 + float ret = RSSI_pin.read(); + if (ret >= 255) { + return 255; + } + return (uint8_t)ret; +#else + return 0; +#endif +}