mirror of https://github.com/ArduPilot/ardupilot
Copter: Add RSSI_RANGE parameter
Added ability to rescale rssi input voltage. Useful for receivers like FrSky which have 3.3V output.
This commit is contained in:
parent
21cda96f67
commit
cb17a5bdb6
|
@ -92,7 +92,8 @@ public:
|
|||
k_param_gps_hdop_good,
|
||||
k_param_battery,
|
||||
k_param_fs_batt_mah,
|
||||
k_param_angle_rate_max, // 38
|
||||
k_param_angle_rate_max,
|
||||
k_param_rssi_range, // 39
|
||||
|
||||
// 65: AP_Limits Library
|
||||
k_param_limits = 65, // deprecated - remove
|
||||
|
@ -313,6 +314,7 @@ public:
|
|||
AP_Int16 rtl_alt_final;
|
||||
|
||||
AP_Int8 rssi_pin;
|
||||
AP_Float rssi_range; // allows to set max voltage for rssi pin such as 5.0, 3.3 etc.
|
||||
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
|
||||
AP_Int16 angle_max; // maximum lean angle of the copter in centi-degrees
|
||||
AP_Int32 angle_rate_max; // maximum rotation rate in roll/pitch axis requested by angle controller used in stabilize, loiter, rtl, auto flight modes
|
||||
|
|
|
@ -181,11 +181,19 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
|
||||
// @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
|
||||
// @Description: This selects an analog pin for the receiver RSSI voltage. It assumes the voltage is RSSI_RANGE for max rssi, 0V for minimum
|
||||
// @Values: -1:Disabled, 0:A0, 1:A1, 2:A2, 13:A13
|
||||
// @User: Standard
|
||||
GSCALAR(rssi_pin, "RSSI_PIN", -1),
|
||||
|
||||
// @Param: RSSI_RANGE
|
||||
// @DisplayName: Receiver RSSI voltage range
|
||||
// @Description: Receiver RSSI voltage range
|
||||
// @Units: Volt
|
||||
// @Values: 3.3:3.3V, 5.0:5V
|
||||
// @User: Standard
|
||||
GSCALAR(rssi_range, "RSSI_RANGE", 5.0),
|
||||
|
||||
// @Param: WP_YAW_BEHAVIOR
|
||||
// @DisplayName: Yaw behaviour during missions
|
||||
// @Description: Determines how the autopilot controls the yaw during missions and RTL
|
||||
|
|
|
@ -119,7 +119,12 @@ static void read_battery(void)
|
|||
// RC_CHANNELS_SCALED message
|
||||
void read_receiver_rssi(void)
|
||||
{
|
||||
rssi_analog_source->set_pin(g.rssi_pin);
|
||||
float ret = rssi_analog_source->voltage_average() * 50;
|
||||
receiver_rssi = constrain_int16(ret, 0, 255);
|
||||
// avoid divide by zero
|
||||
if (g.rssi_range <= 0) {
|
||||
receiver_rssi = 0;
|
||||
}else{
|
||||
rssi_analog_source->set_pin(g.rssi_pin);
|
||||
float ret = rssi_analog_source->voltage_average() * 255 / g.rssi_range;
|
||||
receiver_rssi = constrain_int16(ret, 0, 255);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue