@ -13,7 +13,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = {
@@ -13,7 +13,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
// @Values: -1:Not Used,11:PX4-airspeed port, 15:Pixhawk-airspeed port,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6
// @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 ) ,