AP_RangeFinder: update Type and Pin parameter values
The _TYPE change is to remove the "v2" from the LidarLite description because both v2 and v3 are supported
The _PIN change is to make it more clear that any of the auxiliary pwm pins can be used for PWM input
// @Description: Analog pin that rangefinder is connected to. Set to 11 on PX4 for the analog 'airspeed' port. Set to 15 on the Pixhawk for the analog 'airspeed' port.
// @Values: -1:Not Used,11:PX4-airspeed port, 15:Pixhawk-airspeed port
// @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