APM:Libraries
RangeFinder.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #include "RangeFinder.h"
17 #include "AP_RangeFinder_analog.h"
21 #include "AP_RangeFinder_PX4_PWM.h"
22 #include "AP_RangeFinder_BBB_PRU.h"
25 #if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
26  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && \
27  defined(HAVE_LIBIIO)
28 #include "AP_RangeFinder_Bebop.h"
29 #endif
30 #include "AP_RangeFinder_MAVLink.h"
34 #include "AP_RangeFinder_VL53L0X.h"
35 #include "AP_RangeFinder_NMEA.h"
36 #include "AP_RangeFinder_Wasp.h"
39 
40 extern const AP_HAL::HAL &hal;
41 
42 // table of user settable parameters
44  // @Param: _TYPE
45  // @DisplayName: Rangefinder type
46  // @Description: What type of rangefinder device that is connected
47  // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X,17:NMEA,18:WASP-200,19:BenewakeTF02,20:BenewakeTFmini
48  // @User: Standard
49  AP_GROUPINFO("_TYPE", 0, RangeFinder, state[0].type, 0),
50 
51  // @Param: _PIN
52  // @DisplayName: Rangefinder pin
53  // @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.
54  // @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
55  // @User: Standard
56  AP_GROUPINFO("_PIN", 1, RangeFinder, state[0].pin, -1),
57 
58  // @Param: _SCALING
59  // @DisplayName: Rangefinder scaling
60  // @Description: Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
61  // @Units: m/V
62  // @Increment: 0.001
63  // @User: Standard
64  AP_GROUPINFO("_SCALING", 2, RangeFinder, state[0].scaling, 3.0f),
65 
66  // @Param: _OFFSET
67  // @DisplayName: rangefinder offset
68  // @Description: Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM and I2C Lidars
69  // @Units: V
70  // @Increment: 0.001
71  // @User: Standard
72  AP_GROUPINFO("_OFFSET", 3, RangeFinder, state[0].offset, 0.0f),
73 
74  // @Param: _FUNCTION
75  // @DisplayName: Rangefinder function
76  // @Description: Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
77  // @Values: 0:Linear,1:Inverted,2:Hyperbolic
78  // @User: Standard
79  AP_GROUPINFO("_FUNCTION", 4, RangeFinder, state[0].function, 0),
80 
81  // @Param: _MIN_CM
82  // @DisplayName: Rangefinder minimum distance
83  // @Description: Minimum distance in centimeters that rangefinder can reliably read
84  // @Units: cm
85  // @Increment: 1
86  // @User: Standard
87  AP_GROUPINFO("_MIN_CM", 5, RangeFinder, state[0].min_distance_cm, 20),
88 
89  // @Param: _MAX_CM
90  // @DisplayName: Rangefinder maximum distance
91  // @Description: Maximum distance in centimeters that rangefinder can reliably read
92  // @Units: cm
93  // @Increment: 1
94  // @User: Standard
95  AP_GROUPINFO("_MAX_CM", 6, RangeFinder, state[0].max_distance_cm, 700),
96 
97  // @Param: _STOP_PIN
98  // @DisplayName: Rangefinder stop pin
99  // @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.
100  // @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
101  // @User: Standard
102  AP_GROUPINFO("_STOP_PIN", 7, RangeFinder, state[0].stop_pin, -1),
103 
104  // @Param: _SETTLE
105  // @DisplayName: Rangefinder settle time
106  // @Description: The time in milliseconds that the rangefinder reading takes to settle. This is only used when a STOP_PIN is specified. It determines how long we have to wait for the rangefinder to give a reading after we set the STOP_PIN high. For a sonar rangefinder with a range of around 7m this would need to be around 50 milliseconds to allow for the sonar pulse to travel to the target and back again.
107  // @Units: ms
108  // @Increment: 1
109  // @User: Standard
110  AP_GROUPINFO("_SETTLE", 8, RangeFinder, state[0].settle_time_ms, 0),
111 
112  // @Param: _RMETRIC
113  // @DisplayName: Ratiometric
114  // @Description: This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
115  // @Values: 0:No,1:Yes
116  // @User: Standard
117  AP_GROUPINFO("_RMETRIC", 9, RangeFinder, state[0].ratiometric, 1),
118 
119  // @Param: _PWRRNG
120  // @DisplayName: Powersave range
121  // @Description: This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
122  // @Units: m
123  // @Range: 0 32767
124  // @User: Standard
125  AP_GROUPINFO("_PWRRNG", 10, RangeFinder, _powersave_range, 0),
126 
127  // @Param: _GNDCLEAR
128  // @DisplayName: Distance (in cm) from the range finder to the ground
129  // @Description: This parameter sets the expected range measurement(in cm) that the range finder should return when the vehicle is on the ground.
130  // @Units: cm
131  // @Range: 5 127
132  // @Increment: 1
133  // @User: Standard
134  AP_GROUPINFO("_GNDCLEAR", 11, RangeFinder, state[0].ground_clearance_cm, RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT),
135 
136  // @Param: _ADDR
137  // @DisplayName: Bus address of sensor
138  // @Description: This sets the bus address of the sensor, where applicable. Used for the LightWare I2C sensor to allow for multiple sensors on different addresses. A value of 0 disables the sensor.
139  // @Range: 0 127
140  // @Increment: 1
141  // @User: Standard
142  AP_GROUPINFO("_ADDR", 23, RangeFinder, state[0].address, 0),
143 
144  // @Param: _POS_X
145  // @DisplayName: X position offset
146  // @Description: X position of the first rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
147  // @Units: m
148  // @User: Advanced
149 
150  // @Param: _POS_Y
151  // @DisplayName: Y position offset
152  // @Description: Y position of the first rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
153  // @Units: m
154  // @User: Advanced
155 
156  // @Param: _POS_Z
157  // @DisplayName: Z position offset
158  // @Description: Z position of the first rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
159  // @Units: m
160  // @User: Advanced
161  AP_GROUPINFO("_POS", 49, RangeFinder, state[0].pos_offset, 0.0f),
162 
163  // @Param: _ORIENT
164  // @DisplayName: Rangefinder orientation
165  // @Description: Orientation of rangefinder
166  // @Values: 0:Forward, 1:Forward-Right, 2:Right, 3:Back-Right, 4:Back, 5:Back-Left, 6:Left, 7:Forward-Left, 24:Up, 25:Down
167  // @User: Advanced
168  AP_GROUPINFO("_ORIENT", 53, RangeFinder, state[0].orientation, ROTATION_PITCH_270),
169 
170  // @Group: _
171  // @Path: AP_RangeFinder_Wasp.cpp
172  AP_SUBGROUPVARPTR(drivers[0], "_", 57, RangeFinder, backend_var_info[0]),
173 
174 #if RANGEFINDER_MAX_INSTANCES > 1
175  // @Param: 2_TYPE
176  // @DisplayName: Second Rangefinder type
177  // @Description: What type of rangefinder device that is connected
178  // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X,17:NMEA,18:WASP-200,19:BenewakeTF02,20:BenewakeTFmini
179  // @User: Advanced
180  AP_GROUPINFO("2_TYPE", 12, RangeFinder, state[1].type, 0),
181 
182  // @Param: 2_PIN
183  // @DisplayName: Rangefinder pin
184  // @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.
185  // @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
186  // @User: Advanced
187  AP_GROUPINFO("2_PIN", 13, RangeFinder, state[1].pin, -1),
188 
189  // @Param: 2_SCALING
190  // @DisplayName: Rangefinder scaling
191  // @Description: Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
192  // @Units: m/V
193  // @Increment: 0.001
194  // @User: Advanced
195  AP_GROUPINFO("2_SCALING", 14, RangeFinder, state[1].scaling, 3.0f),
196 
197  // @Param: 2_OFFSET
198  // @DisplayName: rangefinder offset
199  // @Description: Offset in volts for zero distance
200  // @Units: V
201  // @Increment: 0.001
202  // @User: Advanced
203  AP_GROUPINFO("2_OFFSET", 15, RangeFinder, state[1].offset, 0.0f),
204 
205  // @Param: 2_FUNCTION
206  // @DisplayName: Rangefinder function
207  // @Description: Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
208  // @Values: 0:Linear,1:Inverted,2:Hyperbolic
209  // @User: Advanced
210  AP_GROUPINFO("2_FUNCTION", 16, RangeFinder, state[1].function, 0),
211 
212  // @Param: 2_MIN_CM
213  // @DisplayName: Rangefinder minimum distance
214  // @Description: Minimum distance in centimeters that rangefinder can reliably read
215  // @Units: cm
216  // @Increment: 1
217  // @User: Advanced
218  AP_GROUPINFO("2_MIN_CM", 17, RangeFinder, state[1].min_distance_cm, 20),
219 
220  // @Param: 2_MAX_CM
221  // @DisplayName: Rangefinder maximum distance
222  // @Description: Maximum distance in centimeters that rangefinder can reliably read
223  // @Units: cm
224  // @Increment: 1
225  // @User: Advanced
226  AP_GROUPINFO("2_MAX_CM", 18, RangeFinder, state[1].max_distance_cm, 700),
227 
228  // @Param: 2_STOP_PIN
229  // @DisplayName: Rangefinder stop pin
230  // @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.
231  // @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
232  // @User: Advanced
233  AP_GROUPINFO("2_STOP_PIN", 19, RangeFinder, state[1].stop_pin, -1),
234 
235  // @Param: 2_SETTLE
236  // @DisplayName: Sonar settle time
237  // @Description: The time in milliseconds that the rangefinder reading takes to settle. This is only used when a STOP_PIN is specified. It determines how long we have to wait for the rangefinder to give a reading after we set the STOP_PIN high. For a sonar rangefinder with a range of around 7m this would need to be around 50 milliseconds to allow for the sonar pulse to travel to the target and back again.
238  // @Units: ms
239  // @Increment: 1
240  // @User: Advanced
241  AP_GROUPINFO("2_SETTLE", 20, RangeFinder, state[1].settle_time_ms, 0),
242 
243  // @Param: 2_RMETRIC
244  // @DisplayName: Ratiometric
245  // @Description: This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
246  // @Values: 0:No,1:Yes
247  // @User: Advanced
248  AP_GROUPINFO("2_RMETRIC", 21, RangeFinder, state[1].ratiometric, 1),
249 
250  // @Param: 2_GNDCLEAR
251  // @DisplayName: Distance (in cm) from the second range finder to the ground
252  // @Description: This parameter sets the expected range measurement(in cm) that the second range finder should return when the vehicle is on the ground.
253  // @Units: cm
254  // @Range: 0 127
255  // @Increment: 1
256  // @User: Advanced
257  AP_GROUPINFO("2_GNDCLEAR", 22, RangeFinder, state[1].ground_clearance_cm, RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT),
258 
259  // @Param: 2_ADDR
260  // @DisplayName: Bus address of second rangefinder
261  // @Description: This sets the bus address of the sensor, where applicable. Used for the LightWare I2C sensor to allow for multiple sensors on different addresses. A value of 0 disables the sensor.
262  // @Range: 0 127
263  // @Increment: 1
264  // @User: Advanced
265  AP_GROUPINFO("2_ADDR", 24, RangeFinder, state[1].address, 0),
266 
267  // @Param: 2_POS_X
268  // @DisplayName: X position offset
269  // @Description: X position of the second rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
270  // @Units: m
271  // @User: Advanced
272 
273  // @Param: 2_POS_Y
274  // @DisplayName: Y position offset
275  // @Description: Y position of the second rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
276  // @Units: m
277  // @User: Advanced
278 
279  // @Param: 2_POS_Z
280  // @DisplayName: Z position offset
281  // @Description: Z position of the second rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
282  // @Units: m
283  // @User: Advanced
284  AP_GROUPINFO("2_POS", 50, RangeFinder, state[1].pos_offset, 0.0f),
285 
286  // @Param: 2_ORIENT
287  // @DisplayName: Rangefinder 2 orientation
288  // @Description: Orientation of 2nd rangefinder
289  // @Values: 0:Forward, 1:Forward-Right, 2:Right, 3:Back-Right, 4:Back, 5:Back-Left, 6:Left, 7:Forward-Left, 24:Up, 25:Down
290  // @User: Advanced
291  AP_GROUPINFO("2_ORIENT", 54, RangeFinder, state[1].orientation, ROTATION_PITCH_270),
292 
293  // @Group: 2_
294  // @Path: AP_RangeFinder_Wasp.cpp
295  AP_SUBGROUPVARPTR(drivers[1], "2_", 58, RangeFinder, backend_var_info[1]),
296 #endif
297 
298 #if RANGEFINDER_MAX_INSTANCES > 2
299 
300  // @Param: 3_TYPE
301  // @DisplayName: Third Rangefinder type
302  // @Description: What type of rangefinder device that is connected
303  // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X,17:NMEA,18:WASP-200,19:BenewakeTF02,20:BenewakeTFmini
304  // @User: Advanced
305  AP_GROUPINFO("3_TYPE", 25, RangeFinder, state[2].type, 0),
306 
307  // @Param: 3_PIN
308  // @DisplayName: Rangefinder pin
309  // @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.
310  // @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
311  // @User: Advanced
312  AP_GROUPINFO("3_PIN", 26, RangeFinder, state[2].pin, -1),
313 
314  // @Param: 3_SCALING
315  // @DisplayName: Rangefinder scaling
316  // @Description: Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
317  // @Units: m/V
318  // @Increment: 0.001
319  // @User: Advanced
320  AP_GROUPINFO("3_SCALING", 27, RangeFinder, state[2].scaling, 3.0f),
321 
322  // @Param: 3_OFFSET
323  // @DisplayName: rangefinder offset
324  // @Description: Offset in volts for zero distance
325  // @Units: V
326  // @Increment: 0.001
327  // @User: Advanced
328  AP_GROUPINFO("3_OFFSET", 28, RangeFinder, state[2].offset, 0.0f),
329 
330  // @Param: 3_FUNCTION
331  // @DisplayName: Rangefinder function
332  // @Description: Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
333  // @Values: 0:Linear,1:Inverted,2:Hyperbolic
334  // @User: Advanced
335  AP_GROUPINFO("3_FUNCTION", 29, RangeFinder, state[2].function, 0),
336 
337  // @Param: 3_MIN_CM
338  // @DisplayName: Rangefinder minimum distance
339  // @Description: Minimum distance in centimeters that rangefinder can reliably read
340  // @Units: cm
341  // @Increment: 1
342  // @User: Advanced
343  AP_GROUPINFO("3_MIN_CM", 30, RangeFinder, state[2].min_distance_cm, 20),
344 
345  // @Param: 3_MAX_CM
346  // @DisplayName: Rangefinder maximum distance
347  // @Description: Maximum distance in centimeters that rangefinder can reliably read
348  // @Units: cm
349  // @Increment: 1
350  // @User: Advanced
351  AP_GROUPINFO("3_MAX_CM", 31, RangeFinder, state[2].max_distance_cm, 700),
352 
353  // @Param: 3_STOP_PIN
354  // @DisplayName: Rangefinder stop pin
355  // @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.
356  // @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
357  // @User: Advanced
358  AP_GROUPINFO("3_STOP_PIN", 32, RangeFinder, state[2].stop_pin, -1),
359 
360  // @Param: 3_SETTLE
361  // @DisplayName: Sonar settle time
362  // @Description: The time in milliseconds that the rangefinder reading takes to settle. This is only used when a STOP_PIN is specified. It determines how long we have to wait for the rangefinder to give a reading after we set the STOP_PIN high. For a sonar rangefinder with a range of around 7m this would need to be around 50 milliseconds to allow for the sonar pulse to travel to the target and back again.
363  // @Units: ms
364  // @Increment: 1
365  // @User: Advanced
366  AP_GROUPINFO("3_SETTLE", 33, RangeFinder, state[2].settle_time_ms, 0),
367 
368  // @Param: 3_RMETRIC
369  // @DisplayName: Ratiometric
370  // @Description: This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
371  // @Values: 0:No,1:Yes
372  // @User: Advanced
373  AP_GROUPINFO("3_RMETRIC", 34, RangeFinder, state[2].ratiometric, 1),
374 
375  // @Param: 3_GNDCLEAR
376  // @DisplayName: Distance (in cm) from the third range finder to the ground
377  // @Description: This parameter sets the expected range measurement(in cm) that the third range finder should return when the vehicle is on the ground.
378  // @Units: cm
379  // @Range: 0 127
380  // @Increment: 1
381  // @User: Advanced
382  AP_GROUPINFO("3_GNDCLEAR", 35, RangeFinder, state[2].ground_clearance_cm, RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT),
383 
384  // @Param: 3_ADDR
385  // @DisplayName: Bus address of third rangefinder
386  // @Description: This sets the bus address of the sensor, where applicable. Used for the LightWare I2C sensor to allow for multiple sensors on different addresses. A value of 0 disables the sensor.
387  // @Range: 0 127
388  // @Increment: 1
389  // @User: Advanced
390  AP_GROUPINFO("3_ADDR", 36, RangeFinder, state[2].address, 0),
391 
392  // @Param: 3_POS_X
393  // @DisplayName: X position offset
394  // @Description: X position of the third rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
395  // @Units: m
396  // @User: Advanced
397 
398  // @Param: 3_POS_Y
399  // @DisplayName: Y position offset
400  // @Description: Y position of the third rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
401  // @Units: m
402  // @User: Advanced
403 
404  // @Param: 3_POS_Z
405  // @DisplayName: Z position offset
406  // @Description: Z position of the third rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
407  // @Units: m
408  // @User: Advanced
409  AP_GROUPINFO("3_POS", 51, RangeFinder, state[2].pos_offset, 0.0f),
410 
411  // @Param: 3_ORIENT
412  // @DisplayName: Rangefinder 3 orientation
413  // @Description: Orientation of 3rd rangefinder
414  // @Values: 0:Forward, 1:Forward-Right, 2:Right, 3:Back-Right, 4:Back, 5:Back-Left, 6:Left, 7:Forward-Left, 24:Up, 25:Down
415  // @User: Advanced
416  AP_GROUPINFO("3_ORIENT", 55, RangeFinder, state[2].orientation, ROTATION_PITCH_270),
417 
418  // @Group: 3_
419  // @Path: AP_RangeFinder_Wasp.cpp
420  AP_SUBGROUPVARPTR(drivers[2], "3_", 59, RangeFinder, backend_var_info[2]),
421 #endif
422 
423 #if RANGEFINDER_MAX_INSTANCES > 3
424 
425  // @Param: 4_TYPE
426  // @DisplayName: Fourth Rangefinder type
427  // @Description: What type of rangefinder device that is connected
428  // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLiteV2-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:uLanding,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X,17:NMEA,18:WASP-200,19:BenewakeTF02,20:BenewakeTFmini
429  // @User: Advanced
430  AP_GROUPINFO("4_TYPE", 37, RangeFinder, state[3].type, 0),
431 
432  // @Param: 4_PIN
433  // @DisplayName: Rangefinder pin
434  // @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.
435  // @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
436  // @User: Advanced
437  AP_GROUPINFO("4_PIN", 38, RangeFinder, state[3].pin, -1),
438 
439  // @Param: 4_SCALING
440  // @DisplayName: Rangefinder scaling
441  // @Description: Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
442  // @Units: m/V
443  // @Increment: 0.001
444  // @User: Advanced
445  AP_GROUPINFO("4_SCALING", 39, RangeFinder, state[3].scaling, 3.0f),
446 
447  // @Param: 4_OFFSET
448  // @DisplayName: rangefinder offset
449  // @Description: Offset in volts for zero distance
450  // @Units: V
451  // @Increment: 0.001
452  // @User: Advanced
453  AP_GROUPINFO("4_OFFSET", 40, RangeFinder, state[3].offset, 0.0f),
454 
455  // @Param: 4_FUNCTION
456  // @DisplayName: Rangefinder function
457  // @Description: Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
458  // @Values: 0:Linear,1:Inverted,2:Hyperbolic
459  // @User: Advanced
460  AP_GROUPINFO("4_FUNCTION", 41, RangeFinder, state[3].function, 0),
461 
462  // @Param: 4_MIN_CM
463  // @DisplayName: Rangefinder minimum distance
464  // @Description: Minimum distance in centimeters that rangefinder can reliably read
465  // @Units: cm
466  // @Increment: 1
467  // @User: Advanced
468  AP_GROUPINFO("4_MIN_CM", 42, RangeFinder, state[3].min_distance_cm, 20),
469 
470  // @Param: 4_MAX_CM
471  // @DisplayName: Rangefinder maximum distance
472  // @Description: Maximum distance in centimeters that rangefinder can reliably read
473  // @Units: cm
474  // @Increment: 1
475  // @User: Advanced
476  AP_GROUPINFO("4_MAX_CM", 43, RangeFinder, state[3].max_distance_cm, 700),
477 
478  // @Param: 4_STOP_PIN
479  // @DisplayName: Rangefinder stop pin
480  // @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.
481  // @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
482  // @User: Advanced
483  AP_GROUPINFO("4_STOP_PIN", 44, RangeFinder, state[3].stop_pin, -1),
484 
485  // @Param: 4_SETTLE
486  // @DisplayName: Sonar settle time
487  // @Description: The time in milliseconds that the rangefinder reading takes to settle. This is only used when a STOP_PIN is specified. It determines how long we have to wait for the rangefinder to give a reading after we set the STOP_PIN high. For a sonar rangefinder with a range of around 7m this would need to be around 50 milliseconds to allow for the sonar pulse to travel to the target and back again.
488  // @Units: ms
489  // @Increment: 1
490  // @User: Advanced
491  AP_GROUPINFO("4_SETTLE", 45, RangeFinder, state[3].settle_time_ms, 0),
492 
493  // @Param: 4_RMETRIC
494  // @DisplayName: Ratiometric
495  // @Description: This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
496  // @Values: 0:No,1:Yes
497  // @User: Advanced
498  AP_GROUPINFO("4_RMETRIC", 46, RangeFinder, state[3].ratiometric, 1),
499 
500  // @Param: 4_GNDCLEAR
501  // @DisplayName: Distance (in cm) from the fourth range finder to the ground
502  // @Description: This parameter sets the expected range measurement(in cm) that the fourth range finder should return when the vehicle is on the ground.
503  // @Units: cm
504  // @Range: 0 127
505  // @Increment: 1
506  // @User: Advanced
507  AP_GROUPINFO("4_GNDCLEAR", 47, RangeFinder, state[3].ground_clearance_cm, RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT),
508 
509  // @Param: 4_ADDR
510  // @DisplayName: Bus address of fourth rangefinder
511  // @Description: This sets the bus address of the sensor, where applicable. Used for the LightWare I2C sensor to allow for multiple sensors on different addresses. A value of 0 disables the sensor.
512  // @Range: 0 127
513  // @Increment: 1
514  // @User: Advanced
515  AP_GROUPINFO("4_ADDR", 48, RangeFinder, state[3].address, 0),
516 
517  // @Param: 4_POS_X
518  // @DisplayName: X position offset
519  // @Description: X position of the fourth rangefinder in body frame. Use the zero range datum point if supplied.
520  // @Units: m
521  // @User: Advanced
522 
523  // @Param: 4_POS_Y
524  // @DisplayName: Y position offset
525  // @Description: Y position of the fourth rangefinder in body frame. Use the zero range datum point if supplied.
526  // @Units: m
527  // @User: Advanced
528 
529  // @Param: 4_POS_Z
530  // @DisplayName: Z position offset
531  // @Description: Z position of the fourth rangefinder in body frame. Use the zero range datum point if supplied.
532  // @Units: m
533  // @User: Advanced
534  AP_GROUPINFO("4_POS", 52, RangeFinder, state[3].pos_offset, 0.0f),
535 
536  // @Param: 4_ORIENT
537  // @DisplayName: Rangefinder 4 orientation
538  // @Description: Orientation of 4th range finder
539  // @Values: 0:Forward, 1:Forward-Right, 2:Right, 3:Back-Right, 4:Back, 5:Back-Left, 6:Left, 7:Forward-Left, 24:Up, 25:Down
540  // @User: Advanced
541  AP_GROUPINFO("4_ORIENT", 56, RangeFinder, state[3].orientation, ROTATION_PITCH_270),
542 
543  // @Group: 4_
544  // @Path: AP_RangeFinder_Wasp.cpp
545  AP_SUBGROUPVARPTR(drivers[3], "4_", 60, RangeFinder, backend_var_info[3]),
546 #endif
547 
549 };
550 
552 
553 RangeFinder::RangeFinder(AP_SerialManager &_serial_manager, enum Rotation orientation_default) :
554  num_instances(0),
555  estimated_terrain_height(0),
556  serial_manager(_serial_manager)
557 {
559 
560  // set orientation defaults
561  for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
562  state[i].orientation.set_default(orientation_default);
563  }
564 
565 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
566  if (_singleton != nullptr) {
567  AP_HAL::panic("Rangefinder must be singleton");
568  }
569 #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
570  _singleton = this;
571 }
572 
573 /*
574  initialise the RangeFinder class. We do detection of attached range
575  finders here. For now we won't allow for hot-plugging of
576  rangefinders.
577  */
579 {
580  if (num_instances != 0) {
581  // init called a 2nd time?
582  return;
583  }
584  for (uint8_t i=0, serial_instance = 0; i<RANGEFINDER_MAX_INSTANCES; i++) {
585  // serial_instance will be increased inside detect_instance
586  // if a serial driver is loaded for this instance
587  detect_instance(i, serial_instance);
588  if (drivers[i] != nullptr) {
589  // we loaded a driver for this instance, so it must be
590  // present (although it may not be healthy)
591  num_instances = i+1;
592  }
593  // initialise pre-arm check variables
594  state[i].pre_arm_check = false;
595  state[i].pre_arm_distance_min = 9999; // initialise to an arbitrary large value
597 
598  // initialise status
600  state[i].range_valid_count = 0;
601  }
602 }
603 
604 /*
605  update RangeFinder state for all instances. This should be called at
606  around 10Hz by main loop
607  */
609 {
610  for (uint8_t i=0; i<num_instances; i++) {
611  if (drivers[i] != nullptr) {
612  if (state[i].type == RangeFinder_TYPE_NONE) {
613  // allow user to disable a rangefinder at runtime
615  state[i].range_valid_count = 0;
616  continue;
617  }
618  drivers[i]->update();
620  }
621  }
622 }
623 
625 {
626  if (!backend) {
627  return false;
628  }
630  AP_HAL::panic("Too many RANGERS backends");
631  }
632 
633  drivers[num_instances++] = backend;
634  return true;
635 }
636 
637 /*
638  detect if an instance of a rangefinder is connected.
639  */
640 void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
641 {
642  enum RangeFinder_Type _type = (enum RangeFinder_Type)state[instance].type.get();
643  switch (_type) {
646  if (!_add_backend(AP_RangeFinder_PulsedLightLRF::detect(1, state[instance], _type))) {
648  }
649  break;
655  }
656  break;
658  if (state[instance].address) {
659 #ifdef HAL_RANGEFINDER_LIGHTWARE_I2C_BUS
661  hal.i2c_mgr->get_device(HAL_RANGEFINDER_LIGHTWARE_I2C_BUS, state[instance].address)));
662 #else
664  hal.i2c_mgr->get_device(1, state[instance].address)))) {
666  hal.i2c_mgr->get_device(0, state[instance].address)));
667  }
668 #endif
669  }
670  break;
672  if (state[instance].address) {
674  hal.i2c_mgr->get_device(1, state[instance].address)))) {
676  hal.i2c_mgr->get_device(0, state[instance].address)));
677  }
678  }
679  break;
682  hal.i2c_mgr->get_device(1, 0x29)))) {
684  hal.i2c_mgr->get_device(0, 0x29)));
685  }
686  break;
687 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
691  }
692  break;
693 #endif
694 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
697  drivers[instance] = new AP_RangeFinder_BBB_PRU(state[instance]);
698  }
699  break;
700 #endif
703  drivers[instance] = new AP_RangeFinder_LightWareSerial(state[instance], serial_manager, serial_instance++);
704  }
705  break;
707  if (AP_RangeFinder_LeddarOne::detect(serial_manager, serial_instance)) {
708  drivers[instance] = new AP_RangeFinder_LeddarOne(state[instance], serial_manager, serial_instance++);
709  }
710  break;
712  if (AP_RangeFinder_uLanding::detect(serial_manager, serial_instance)) {
713  drivers[instance] = new AP_RangeFinder_uLanding(state[instance], serial_manager, serial_instance++);
714  }
715  break;
716 #if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
717  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO)
720  drivers[instance] = new AP_RangeFinder_Bebop(state[instance]);
721  }
722  break;
723 #endif
726  drivers[instance] = new AP_RangeFinder_MAVLink(state[instance]);
727  }
728  break;
731  drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(state[instance], serial_manager, serial_instance++);
732  }
733  break;
735  // note that analog will always come back as present if the pin is valid
736  if (AP_RangeFinder_analog::detect(state[instance])) {
737  drivers[instance] = new AP_RangeFinder_analog(state[instance]);
738  }
739  break;
741  if (AP_RangeFinder_NMEA::detect(serial_manager, serial_instance)) {
742  drivers[instance] = new AP_RangeFinder_NMEA(state[instance], serial_manager, serial_instance++);
743  }
744  break;
746  if (AP_RangeFinder_Wasp::detect(serial_manager, serial_instance)) {
747  drivers[instance] = new AP_RangeFinder_Wasp(state[instance], serial_manager, serial_instance++);
748  }
749  break;
751  if (AP_RangeFinder_Benewake::detect(serial_manager, serial_instance)) {
752  drivers[instance] = new AP_RangeFinder_Benewake(state[instance], serial_manager, serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TF02);
753  }
754  break;
756  if (AP_RangeFinder_Benewake::detect(serial_manager, serial_instance)) {
757  drivers[instance] = new AP_RangeFinder_Benewake(state[instance], serial_manager, serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TFmini);
758  }
759  break;
760  default:
761  break;
762  }
763 
764  // if the backend has some local parameters then make those available in the tree
765  if (drivers[instance] && state[instance].var_info) {
766  backend_var_info[instance] = state[instance].var_info;
768  }
769 }
770 
772  if (id >= num_instances) {
773  return nullptr;
774  }
775  if (drivers[id] != nullptr) {
776  if (drivers[id]->type() == RangeFinder_TYPE_NONE) {
777  // pretend it isn't here; disabled at runtime?
778  return nullptr;
779  }
780  }
781  return drivers[id];
782 };
783 
785 {
786  AP_RangeFinder_Backend *backend = find_instance(orientation);
787  if (backend == nullptr) {
789  }
790  return backend->status();
791 }
792 
793 void RangeFinder::handle_msg(mavlink_message_t *msg)
794 {
795  uint8_t i;
796  for (i=0; i<num_instances; i++) {
797  if ((drivers[i] != nullptr) && (state[i].type != RangeFinder_TYPE_NONE)) {
798  drivers[i]->handle_msg(msg);
799  }
800  }
801 }
802 
803 // return true if we have a range finder with the specified orientation
804 bool RangeFinder::has_orientation(enum Rotation orientation) const
805 {
806  return (find_instance(orientation) != nullptr);
807 }
808 
809 // find first range finder instance with the specified orientation
811 {
812  for (uint8_t i=0; i<num_instances; i++) {
813  AP_RangeFinder_Backend *backend = get_backend(i);
814  if (backend == nullptr) {
815  continue;
816  }
817  if (backend->orientation() != orientation) {
818  continue;
819  }
820  return backend;
821  }
822  return nullptr;
823 }
824 
825 uint16_t RangeFinder::distance_cm_orient(enum Rotation orientation) const
826 {
827  AP_RangeFinder_Backend *backend = find_instance(orientation);
828  if (backend == nullptr) {
829  return 0;
830  }
831  return backend->distance_cm();
832 }
833 
834 uint16_t RangeFinder::voltage_mv_orient(enum Rotation orientation) const
835 {
836  AP_RangeFinder_Backend *backend = find_instance(orientation);
837  if (backend == nullptr) {
838  return 0;
839  }
840  return backend->voltage_mv();
841 }
842 
843 int16_t RangeFinder::max_distance_cm_orient(enum Rotation orientation) const
844 {
845  AP_RangeFinder_Backend *backend = find_instance(orientation);
846  if (backend == nullptr) {
847  return 0;
848  }
849  return backend->max_distance_cm();
850 }
851 
852 int16_t RangeFinder::min_distance_cm_orient(enum Rotation orientation) const
853 {
854  AP_RangeFinder_Backend *backend = find_instance(orientation);
855  if (backend == nullptr) {
856  return 0;
857  }
858  return backend->min_distance_cm();
859 }
860 
861 int16_t RangeFinder::ground_clearance_cm_orient(enum Rotation orientation) const
862 {
863  AP_RangeFinder_Backend *backend = find_instance(orientation);
864  if (backend == nullptr) {
865  return 0;
866  }
867  return backend->ground_clearance_cm();
868 }
869 
870 bool RangeFinder::has_data_orient(enum Rotation orientation) const
871 {
872  AP_RangeFinder_Backend *backend = find_instance(orientation);
873  if (backend == nullptr) {
874  return false;
875  }
876  return backend->has_data();
877 }
878 
879 uint8_t RangeFinder::range_valid_count_orient(enum Rotation orientation) const
880 {
881  AP_RangeFinder_Backend *backend = find_instance(orientation);
882  if (backend == nullptr) {
883  return 0;
884  }
885  return backend->range_valid_count();
886 }
887 
888 /*
889  returns true if pre-arm checks have passed for all range finders
890  these checks involve the user lifting or rotating the vehicle so that sensor readings between
891  the min and 2m can be captured
892  */
894 {
895  for (uint8_t i=0; i<num_instances; i++) {
896  // if driver is valid but pre_arm_check is false, return false
897  if ((drivers[i] != nullptr) && (state[i].type != RangeFinder_TYPE_NONE) && !state[i].pre_arm_check) {
898  return false;
899  }
900  }
901  return true;
902 }
903 
905 {
906  AP_RangeFinder_Backend *backend = find_instance(orientation);
907  if (backend == nullptr) {
908  return pos_offset_zero;
909  }
910  return backend->get_pos_offset();
911 }
912 
913 MAV_DISTANCE_SENSOR RangeFinder::get_mav_distance_sensor_type_orient(enum Rotation orientation) const
914 {
915  AP_RangeFinder_Backend *backend = find_instance(orientation);
916  if (backend == nullptr) {
917  return MAV_DISTANCE_SENSOR_UNKNOWN;
918  }
919  return backend->get_mav_distance_sensor_type();
920 }
921 
float scaling
Definition: AnalogIn.cpp:40
AP_RangeFinder_Backend * get_backend(uint8_t id) const
bool has_data_orient(enum Rotation orientation) const
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type_orient(enum Rotation orientation) const
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
static RangeFinder * _singleton
Definition: RangeFinder.h:171
uint16_t voltage_mv() const
static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1335
RangeFinder_State state[RANGEFINDER_MAX_INSTANCES]
Definition: RangeFinder.h:173
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
enum Rotation orientation() const
void update(void)
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
uint16_t distance_cm() const
AP_SerialManager & serial_manager
Definition: RangeFinder.h:177
const Vector3f & get_pos_offset_orient(enum Rotation orientation) const
#define RANGEFINDER_MAX_INSTANCES
Definition: RangeFinder.h:24
static AP_RangeFinder_Backend * detect(uint8_t bus, RangeFinder::RangeFinder_State &_state, RangeFinder::RangeFinder_Type rftype)
int16_t ground_clearance_cm() const
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
bool has_orientation(enum Rotation orientation) const
float estimated_terrain_height
Definition: RangeFinder.h:176
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
AP_RangeFinder_Backend * find_instance(enum Rotation orientation) const
uint8_t range_valid_count_orient(enum Rotation orientation) const
virtual void handle_msg(mavlink_message_t *msg)
static const struct AP_Param::GroupInfo var_info[]
Definition: RangeFinder.h:114
ptrdiff_t offset
Definition: AP_Param.h:149
Rotation
Definition: rotations.h:27
const Vector3f & get_pos_offset() const
static bool detect(RangeFinder::RangeFinder_State &_state)
enum RangeFinder_Status status
Definition: RangeFinder.h:86
static bool detect()
void detect_instance(uint8_t instance, uint8_t &serial_instance)
uint8_t num_instances
Definition: RangeFinder.h:175
#define AP_SUBGROUPVARPTR(element, name, idx, thisclazz, var_info)
Definition: AP_Param.h:119
#define AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR
#define f(i)
uint8_t range_valid_count() const
virtual void update()=0
AP_Int16 _powersave_range
Definition: RangeFinder.h:111
bool pre_arm_check() const
uint16_t distance_cm_orient(enum Rotation orientation) const
int16_t max_distance_cm_orient(enum Rotation orientation) const
static int state
Definition: Util.cpp:20
bool _add_backend(AP_RangeFinder_Backend *driver)
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
AP_RangeFinder_Backend * drivers[RANGEFINDER_MAX_INSTANCES]
Definition: RangeFinder.h:174
AP_HAL::I2CDeviceManager * i2c_mgr
Definition: HAL.h:106
Vector3f pos_offset_zero
Definition: RangeFinder.h:178
uint16_t voltage_mv_orient(enum Rotation orientation) const
void handle_msg(mavlink_message_t *msg)
MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const
RangeFinder_Status status_orient(enum Rotation orientation) const
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
#define RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT
Definition: RangeFinder.h:25
RangeFinder(AP_SerialManager &_serial_manager, enum Rotation orientation_default)
const struct AP_Param::GroupInfo * var_info
Definition: RangeFinder.h:106
static const struct AP_Param::GroupInfo * backend_var_info[RANGEFINDER_MAX_INSTANCES]
Definition: RangeFinder.h:109
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
RangeFinder::RangeFinder_Status status() const
int16_t min_distance_cm() const
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
static int8_t pin
Definition: AnalogIn.cpp:15
void init(void)
int16_t ground_clearance_cm_orient(enum Rotation orientation) const
int16_t min_distance_cm_orient(enum Rotation orientation) const
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
#define AP_GROUPEND
Definition: AP_Param.h:121
int16_t max_distance_cm() const
static AP_RangeFinder_Backend * detect(RangeFinder::RangeFinder_State &_state, AP_HAL::OwnPtr< AP_HAL::I2CDevice > i2c_dev)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214