APM: added RSSI_PIN option for receiver RSSI

this allows you to configure the pin for receiver RSSI without
recompiling
This commit is contained in:
Andrew Tridgell 2012-11-06 22:04:41 +11:00
parent 403721f8ca
commit 8652bfee8d
5 changed files with 17 additions and 13 deletions

View File

@ -274,9 +274,9 @@ AP_AnalogSource_ADC pitot_analog_source( &adc,
AP_AnalogSource_Arduino pitot_analog_source(CONFIG_PITOT_SOURCE_ANALOG_PIN, 4.0);
#endif
#if RECEIVER_RSSI_PIN != -1
AP_AnalogSource_Arduino RSSI_pin(RECEIVER_RSSI_PIN, 0.25);
#endif
// a pin for reading the receiver RSSI voltage. The scaling by 0.25
// is to take the 0 to 1024 range down to an 8 bit range for MAVLink
AP_AnalogSource_Arduino RSSI_pin(-1, 0.25);
AP_Relay relay;

View File

@ -138,7 +138,8 @@ public:
//
// Battery monitoring parameters
//
k_param_battery_volt_pin = 168,
k_param_rssi_pin = 167,
k_param_battery_volt_pin,
k_param_battery_curr_pin, // 169
//
@ -341,6 +342,7 @@ public:
AP_Float curr_amp_per_volt;
AP_Float input_voltage;
AP_Int32 pack_capacity; // Battery pack capacity less reserve
AP_Int8 rssi_pin;
AP_Int8 battery_volt_pin;
AP_Int8 battery_curr_pin;
AP_Int8 inverted_flight_ch; // 0=disabled, 1-8 is channel for inverted flight trigger

View File

@ -534,16 +534,24 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: BATT_VOLT_PIN
// @DisplayName: Battery Voltage sensing pin
// @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13.
// @Values: 99:Disabled, 0:A0, 1:A1, 13:A13
// @Values: -1:Disabled, 0:A0, 1:A1, 13:A13
// @User: Standard
GSCALAR(battery_volt_pin, "BATT_VOLT_PIN", BATTERY_VOLT_PIN),
// @Param: BATT_CURR_PIN
// @DisplayName: Battery Current sensing pin
// @Description: Setting this to 0 ~ 13 will enable battery current sensing on pins A0 ~ A13.
// @Values: 99:Disabled, 1:A1, 2:A2, 12:A12
// @Values: -1:Disabled, 1:A1, 2:A2, 12:A12
// @User: Standard
GSCALAR(battery_curr_pin, "BATT_CURR_PIN", BATTERY_CURR_PIN),
// @Param: RSSI_PIN
// @DisplayName: Receiver RSSI sensing pin
// @Description: This selects an analog pin for the receiver RSSI voltage. It assumes the voltage is 5V for max rssi, 0V for minimum
// @Values: -1:Disabled, 0:A0, 1:A1, 13:A13
// @User: Standard
GSCALAR(rssi_pin, "RSSI_PIN", -1),
GSCALAR(inverted_flight_ch, "INVERTEDFLT_CH", 0),
// barometer ground calibration. The GND_ prefix is chosen for

View File

@ -134,11 +134,6 @@
#endif
// pin for receiver RSSI
#ifndef RECEIVER_RSSI_PIN
# define RECEIVER_RSSI_PIN -1
#endif
//////////////////////////////////////////////////////////////////////////////
// IMU Selection
//

View File

@ -64,10 +64,9 @@ static void read_battery(void)
// RC_CHANNELS_SCALED message
void read_receiver_rssi(void)
{
#if RECEIVER_RSSI_PIN != -1
RSSI_pin.set_pin(g.rssi_pin);
float ret = RSSI_pin.read();
receiver_rssi = constrain(ret, 0, 255);
#endif
}