mirror of https://github.com/ArduPilot/ardupilot
Copter: fix RSSI_RANGE param values
The extra .0 after the 5 was causing the mission planner to not display 5V in the dropdown even though the value was 5.
This commit is contained in:
parent
ab46f2d2fe
commit
0d88b602ec
|
@ -197,9 +197,9 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||
// @DisplayName: Receiver RSSI voltage range
|
||||
// @Description: Receiver RSSI voltage range
|
||||
// @Units: Volt
|
||||
// @Values: 3.3:3.3V, 5.0:5V
|
||||
// @Values: 3.3:3.3V, 5:5V
|
||||
// @User: Standard
|
||||
GSCALAR(rssi_range, "RSSI_RANGE", 5.0),
|
||||
GSCALAR(rssi_range, "RSSI_RANGE", 5.0f),
|
||||
|
||||
// @Param: WP_YAW_BEHAVIOR
|
||||
// @DisplayName: Yaw behaviour during missions
|
||||
|
|
Loading…
Reference in New Issue