mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: make metadata more consistent
This commit is contained in:
parent
a03ccd1a8a
commit
f087e9d25d
|
@ -20,7 +20,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = {
|
|||
|
||||
// @Param: PIN
|
||||
// @DisplayName: Rangefinder pin
|
||||
// @Description: Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input. When using analog pin 103, the maximum value of the input in 3.3V. For PWM input, the pin must be configured as a digital GPIO, see the Wiki's "GPIOs" section for details.
|
||||
// @Description: Analog or PWM input pin that rangefinder is connected to. Analog RSSI or Airspeed ports can be used for Analog inputs (some autopilots provide others also), Non-IOMCU Servo/MotorOutputs can be used for PWM input when configured as "GPIOs". Values for some autopilots are given as examples. Search wiki for "Analog pins" for analog pin or "GPIOs", if PWM input type, to determine pin number.
|
||||
// @Values: -1:Not Used,11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6/Pixhawk2 ADC,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6,103:Pixhawk SBUS
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("PIN", 2, AP_RangeFinder_Params, pin, -1),
|
||||
|
|
Loading…
Reference in New Issue