mirror of https://github.com/ArduPilot/ardupilot
AP_WindVane: Fix duplicate values in Param
This commit is contained in:
parent
44d35942b6
commit
59af2fcbbb
|
@ -44,7 +44,7 @@ const AP_Param::GroupInfo AP_WindVane::var_info[] = {
|
||||||
// @Param: DIR_PIN
|
// @Param: DIR_PIN
|
||||||
// @DisplayName: Wind vane analog voltage pin for direction
|
// @DisplayName: Wind vane analog voltage pin for direction
|
||||||
// @Description: Analog input pin to read as wind vane direction
|
// @Description: Analog input pin to read as wind vane direction
|
||||||
// @Values: 11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6,15:Pixhawk2 ADC,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6,103:Pixhawk SBUS
|
// @Values: 11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6/Pixhawk2 ADC,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6,103:Pixhawk SBUS
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("DIR_PIN", 3, AP_WindVane, _dir_analog_pin, WINDVANE_DEFAULT_PIN),
|
AP_GROUPINFO("DIR_PIN", 3, AP_WindVane, _dir_analog_pin, WINDVANE_DEFAULT_PIN),
|
||||||
|
|
||||||
|
@ -118,14 +118,14 @@ const AP_Param::GroupInfo AP_WindVane::var_info[] = {
|
||||||
// @Param: SPEED_PIN
|
// @Param: SPEED_PIN
|
||||||
// @DisplayName: Wind vane speed sensor analog pin
|
// @DisplayName: Wind vane speed sensor analog pin
|
||||||
// @Description: Wind speed analog speed input pin for Modern Devices Wind Sensor rev. p
|
// @Description: Wind speed analog speed input pin for Modern Devices Wind Sensor rev. p
|
||||||
// @Values: 11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6,15:Pixhawk2 ADC,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6,103:Pixhawk SBUS
|
// @Values: 11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6/Pixhawk2 ADC,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6,103:Pixhawk SBUS
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("SPEED_PIN", 12, AP_WindVane, _speed_sensor_speed_pin, WINDSPEED_DEFAULT_SPEED_PIN),
|
AP_GROUPINFO("SPEED_PIN", 12, AP_WindVane, _speed_sensor_speed_pin, WINDSPEED_DEFAULT_SPEED_PIN),
|
||||||
|
|
||||||
// @Param: TEMP_PIN
|
// @Param: TEMP_PIN
|
||||||
// @DisplayName: Wind vane speed sensor analog temp pin
|
// @DisplayName: Wind vane speed sensor analog temp pin
|
||||||
// @Description: Wind speed sensor analog temp input pin for Modern Devices Wind Sensor rev. p, set to -1 to diasble temp readings
|
// @Description: Wind speed sensor analog temp input pin for Modern Devices Wind Sensor rev. p, set to -1 to diasble temp readings
|
||||||
// @Values: 11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6,15:Pixhawk2 ADC,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6,103:Pixhawk SBUS
|
// @Values: 11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6/Pixhawk2 ADC,50:PixhawkAUX1,51:PixhawkAUX2,52:PixhawkAUX3,53:PixhawkAUX4,54:PixhawkAUX5,55:PixhawkAUX6,103:Pixhawk SBUS
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("TEMP_PIN", 13, AP_WindVane, _speed_sensor_temp_pin, WINDSPEED_DEFAULT_TEMP_PIN),
|
AP_GROUPINFO("TEMP_PIN", 13, AP_WindVane, _speed_sensor_temp_pin, WINDSPEED_DEFAULT_TEMP_PIN),
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue