mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_RangeFinder: fix ADC scaling on IOMCU
This commit is contained in:
parent
206a25fbcc
commit
ba9381f40c
@ -12,7 +12,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
|
||||
// @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.
|
||||
// @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
Block a user