mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
RangeFinder: minor param description update
Also initialise primary instance to 0. No functional change.
This commit is contained in:
parent
d49489ca7e
commit
01c669ee15
@ -31,6 +31,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] PROGMEM = {
|
||||
// @Param: _PIN
|
||||
// @DisplayName: Rangefinder pin
|
||||
// @Description: Analog pin that rangefinder is connected to. Set this to 0..9 for the APM2 analog pins. Set to 64 on an APM1 for the dedicated 'airspeed' port on the end of the board. 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, 0:APM2-A0, 1:APM2-A1, 2:APM2-A2, 3:APM2-A3, 4:APM2-A4, 5:APM2-A5, 6:APM2-A6, 7:APM2-A7, 8:APM2-A8, 9:APM2-A9, 11:PX4-airspeed port, 15:Pixhawk-airspeed port, 64:APM1-airspeed port
|
||||
AP_GROUPINFO("_PIN", 1, RangeFinder, _pin[0], -1),
|
||||
|
||||
// @Param: _SCALING
|
||||
@ -70,6 +71,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] PROGMEM = {
|
||||
// @Param: _STOP_PIN
|
||||
// @DisplayName: Rangefinder stop pin
|
||||
// @Description: Digital pin that enables/disables rangefinder measurement for an analog rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This can be used to ensure that multiple sonar rangefinders don't interfere with each other.
|
||||
// @Values: -1:Not Used,50:Pixhawk AUXOUT1,51:Pixhawk AUXOUT2,52:Pixhawk AUXOUT3,53:Pixhawk AUXOUT4,54:Pixhawk AUXOUT5,55:Pixhawk AUXOUT6,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2
|
||||
AP_GROUPINFO("_STOP_PIN", 7, RangeFinder, _stop_pin[0], -1),
|
||||
|
||||
// @Param: _SETTLE
|
||||
@ -97,6 +99,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] PROGMEM = {
|
||||
// @Param: 2_PIN
|
||||
// @DisplayName: Rangefinder pin
|
||||
// @Description: Analog pin that rangefinder is connected to. Set this to 0..9 for the APM2 analog pins. Set to 64 on an APM1 for the dedicated 'airspeed' port on the end of the board. 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, 0:APM2-A0, 1:APM2-A1, 2:APM2-A2, 3:APM2-A3, 4:APM2-A4, 5:APM2-A5, 6:APM2-A6, 7:APM2-A7, 8:APM2-A8, 9:APM2-A9, 11:PX4-airspeed port, 15:Pixhawk-airspeed port, 64:APM1-airspeed port
|
||||
AP_GROUPINFO("2_PIN", 13, RangeFinder, _pin[1], -1),
|
||||
|
||||
// @Param: 2_SCALING
|
||||
@ -136,6 +139,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] PROGMEM = {
|
||||
// @Param: 2_STOP_PIN
|
||||
// @DisplayName: Rangefinder stop pin
|
||||
// @Description: Digital pin that enables/disables rangefinder measurement for an analog rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This can be used to ensure that multiple sonar rangefinders don't interfere with each other.
|
||||
// @Values: -1:Not Used,50:Pixhawk AUXOUT1,51:Pixhawk AUXOUT2,52:Pixhawk AUXOUT3,53:Pixhawk AUXOUT4,54:Pixhawk AUXOUT5,55:Pixhawk AUXOUT6,111:PX4 FMU Relay1,112:PX4 FMU Relay2,113:PX4IO Relay1,114:PX4IO Relay2,115:PX4IO ACC1,116:PX4IO ACC2
|
||||
AP_GROUPINFO("2_STOP_PIN", 19, RangeFinder, _stop_pin[1], -1),
|
||||
|
||||
// @Param: 2_SETTLE
|
||||
|
@ -30,6 +30,7 @@ class RangeFinder
|
||||
{
|
||||
public:
|
||||
RangeFinder(void) :
|
||||
primary_instance(0),
|
||||
num_instances(0)
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
Loading…
Reference in New Issue
Block a user