forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathAP_RangeFinder.cpp
More file actions
985 lines (889 loc) · 31.9 KB
/
AP_RangeFinder.cpp
File metadata and controls
985 lines (889 loc) · 31.9 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "AP_RangeFinder.h"
#if AP_RANGEFINDER_ENABLED
#include "AP_RangeFinder_analog.h"
#include "AP_RangeFinder_PulsedLightLRF.h"
#include "AP_RangeFinder_MaxsonarI2CXL.h"
#include "AP_RangeFinder_MaxsonarSerialLV.h"
#include "AP_RangeFinder_BBB_PRU.h"
#include "AP_RangeFinder_LightWareI2C.h"
#include "AP_RangeFinder_LightWareSerial.h"
#if AP_RANGEFINDER_BEBOP_ENABLED
#include "AP_RangeFinder_Bebop.h"
#endif
#include "AP_RangeFinder_Backend.h"
#include "AP_RangeFinder_Backend_Serial.h"
#include "AP_RangeFinder_MAVLink.h"
#include "AP_RangeFinder_LeddarOne.h"
#include "AP_RangeFinder_USD1_Serial.h"
#include "AP_RangeFinder_TeraRangerI2C.h"
#include "AP_RangeFinder_TeraRanger_Serial.h"
#include "AP_RangeFinder_VL53L0X.h"
#include "AP_RangeFinder_VL53L1X.h"
#include "AP_RangeFinder_NMEA.h"
#include "AP_RangeFinder_Wasp.h"
#include "AP_RangeFinder_Benewake_TF02.h"
#include "AP_RangeFinder_Benewake_TF03.h"
#include "AP_RangeFinder_Benewake_TFMini.h"
#include "AP_RangeFinder_Benewake_TFMiniPlus.h"
#include "AP_RangeFinder_Benewake_TFS20L.h"
#include "AP_RangeFinder_PWM.h"
#include "AP_RangeFinder_GYUS42v2.h"
#include "AP_RangeFinder_HC_SR04.h"
#include "AP_RangeFinder_Bebop.h"
#include "AP_RangeFinder_BLPing.h"
#include "AP_RangeFinder_DroneCAN.h"
#include "AP_RangeFinder_Lanbao.h"
#include "AP_RangeFinder_LeddarVu8.h"
#include "AP_RangeFinder_SITL.h"
#include "AP_RangeFinder_MSP.h"
#include "AP_RangeFinder_USD1_CAN.h"
#include "AP_RangeFinder_Benewake_CAN.h"
#include "AP_RangeFinder_Lua.h"
#include "AP_RangeFinder_NoopLoop.h"
#include "AP_RangeFinder_TOFSenseP_CAN.h"
#include "AP_RangeFinder_NRA24_CAN.h"
#include "AP_RangeFinder_TOFSenseF_I2C.h"
#include "AP_RangeFinder_JRE_Serial.h"
#include "AP_RangeFinder_Ainstein_LR_D1.h"
#include "AP_RangeFinder_RDS02UF.h"
#include "AP_RangeFinder_LightWare_GRF.h"
#include "AP_RangeFinder_DTS6012M.h"
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_Logger/AP_Logger.h>
#include <AP_SerialManager/AP_SerialManager.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_InternalError/AP_InternalError.h>
extern const AP_HAL::HAL &hal;
// table of user settable parameters
const AP_Param::GroupInfo RangeFinder::var_info[] = {
// @Group: 1_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO(params[0], "1_", 25, RangeFinder, AP_RangeFinder_Params),
// @Group: 1_
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp,AP_RangeFinder_LightWare_GRF.cpp
AP_SUBGROUPVARPTR(drivers[0], "1_", 57, RangeFinder, backend_var_info[0]),
#if RANGEFINDER_MAX_INSTANCES > 1
// @Group: 2_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO(params[1], "2_", 27, RangeFinder, AP_RangeFinder_Params),
// @Group: 2_
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp,AP_RangeFinder_LightWare_GRF.cpp
AP_SUBGROUPVARPTR(drivers[1], "2_", 58, RangeFinder, backend_var_info[1]),
#endif
#if RANGEFINDER_MAX_INSTANCES > 2
// @Group: 3_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO(params[2], "3_", 29, RangeFinder, AP_RangeFinder_Params),
// @Group: 3_
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp,AP_RangeFinder_LightWare_GRF.cpp
AP_SUBGROUPVARPTR(drivers[2], "3_", 59, RangeFinder, backend_var_info[2]),
#endif
#if RANGEFINDER_MAX_INSTANCES > 3
// @Group: 4_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO(params[3], "4_", 31, RangeFinder, AP_RangeFinder_Params),
// @Group: 4_
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp,AP_RangeFinder_LightWare_GRF.cpp
AP_SUBGROUPVARPTR(drivers[3], "4_", 60, RangeFinder, backend_var_info[3]),
#endif
#if RANGEFINDER_MAX_INSTANCES > 4
// @Group: 5_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO(params[4], "5_", 33, RangeFinder, AP_RangeFinder_Params),
// @Group: 5_
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp,AP_RangeFinder_LightWare_GRF.cpp
AP_SUBGROUPVARPTR(drivers[4], "5_", 34, RangeFinder, backend_var_info[4]),
#endif
#if RANGEFINDER_MAX_INSTANCES > 5
// @Group: 6_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO(params[5], "6_", 35, RangeFinder, AP_RangeFinder_Params),
// @Group: 6_
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp,AP_RangeFinder_LightWare_GRF.cpp
AP_SUBGROUPVARPTR(drivers[5], "6_", 36, RangeFinder, backend_var_info[5]),
#endif
#if RANGEFINDER_MAX_INSTANCES > 6
// @Group: 7_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO(params[6], "7_", 37, RangeFinder, AP_RangeFinder_Params),
// @Group: 7_
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp,AP_RangeFinder_LightWare_GRF.cpp
AP_SUBGROUPVARPTR(drivers[6], "7_", 38, RangeFinder, backend_var_info[6]),
#endif
#if RANGEFINDER_MAX_INSTANCES > 7
// @Group: 8_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO(params[7], "8_", 39, RangeFinder, AP_RangeFinder_Params),
// @Group: 8_
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp,AP_RangeFinder_LightWare_GRF.cpp
AP_SUBGROUPVARPTR(drivers[7], "8_", 40, RangeFinder, backend_var_info[7]),
#endif
#if RANGEFINDER_MAX_INSTANCES > 8
// @Group: 9_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO(params[8], "9_", 41, RangeFinder, AP_RangeFinder_Params),
// @Group: 9_
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp,AP_RangeFinder_LightWare_GRF.cpp
AP_SUBGROUPVARPTR(drivers[8], "9_", 42, RangeFinder, backend_var_info[8]),
#endif
#if RANGEFINDER_MAX_INSTANCES > 9
// @Group: A_
// @Path: AP_RangeFinder_Params.cpp
AP_SUBGROUPINFO(params[9], "A_", 43, RangeFinder, AP_RangeFinder_Params),
// @Group: A_
// @Path: AP_RangeFinder_Wasp.cpp,AP_RangeFinder_Backend_CAN.cpp,AP_RangeFinder_LightWare_GRF.cpp
AP_SUBGROUPVARPTR(drivers[9], "A_", 44, RangeFinder, backend_var_info[9]),
#endif
AP_GROUPEND
};
const AP_Param::GroupInfo *RangeFinder::backend_var_info[RANGEFINDER_MAX_INSTANCES];
RangeFinder::RangeFinder()
{
AP_Param::setup_object_defaults(this, var_info);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (_singleton != nullptr) {
AP_HAL::panic("Rangefinder must be singleton");
}
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
_singleton = this;
}
void RangeFinder::convert_params(void)
{
// PARAMETER_CONVERSION - Added: Dec-2024 for 4.6->4.7
for (auto &p : params) {
p.convert_min_max_params();
}
}
/*
initialise the RangeFinder class. We do detection of attached range
finders here. For now we won't allow for hot-plugging of
rangefinders.
*/
__INITFUNC__ void RangeFinder::init(enum Rotation orientation_default)
{
convert_params();
if (num_instances != 0) {
// don't re-init if we've found some sensors already
return;
}
// set orientation defaults
for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
params[i].orientation.set_default(orientation_default);
}
for (uint8_t i=0, serial_instance = 0; i<RANGEFINDER_MAX_INSTANCES; i++) {
// serial_instance will be increased inside detect_instance
// if a serial driver is loaded for this instance
WITH_SEMAPHORE(detect_sem);
detect_instance(i, serial_instance);
if (drivers[i] != nullptr) {
// we loaded a driver for this instance, so it must be
// present (although it may not be healthy). We use MAX()
// here as a UAVCAN rangefinder may already have been
// found
num_instances = MAX(num_instances, i+1);
}
// initialise status
state[i].status = Status::NotConnected;
state[i].range_valid_count = 0;
// initialize signal_quality_pct for drivers that don't handle it.
state[i].signal_quality_pct = SIGNAL_QUALITY_UNKNOWN;
}
}
/*
update RangeFinder state for all instances. This should be called at
around 10Hz by main loop
*/
void RangeFinder::update(void)
{
for (uint8_t i=0; i<num_instances; i++) {
if (drivers[i] != nullptr) {
if ((Type)params[i].type.get() == Type::NONE) {
// allow user to disable a rangefinder at runtime
state[i].status = Status::NotConnected;
state[i].range_valid_count = 0;
continue;
}
drivers[i]->update();
}
}
#if HAL_LOGGING_ENABLED
Log_RFND();
#endif
}
__INITFUNC__ bool RangeFinder::_add_backend(AP_RangeFinder_Backend *backend, uint8_t instance, uint8_t serial_instance)
{
if (!backend) {
return false;
}
if (instance >= RANGEFINDER_MAX_INSTANCES) {
AP_HAL::panic("Too many RANGERS backends");
}
if (drivers[instance] != nullptr) {
// we've allocated the same instance twice
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
}
backend->init_serial(serial_instance);
drivers[instance] = backend;
num_instances = MAX(num_instances, instance+1);
return true;
}
/*
* probe all i2c buses for a backend type:
*/
__INITFUNC__ void RangeFinder::probe_i2c_buses(uint8_t instance, uint8_t addr, i2c_probe_fn_t detect_fn)
{
FOREACH_I2C(i) {
auto *device_ptr = hal.i2c_mgr->get_device_ptr(i, addr);
if (device_ptr == nullptr) {
continue;
}
if (_add_backend(detect_fn(state[instance], params[instance], *device_ptr),
instance)) {
return;
}
delete device_ptr;
}
}
/*
detect if an instance of a rangefinder is connected.
*/
__INITFUNC__ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
{
AP_RangeFinder_Backend_Serial *(*serial_create_fn)(RangeFinder::RangeFinder_State&, AP_RangeFinder_Params&) = nullptr;
const Type _type = (Type)params[instance].type.get();
switch (_type) {
#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED
case Type::PLI2C:
case Type::PLI2CV3:
case Type::PLI2CV3HP:
FOREACH_I2C(i) {
if (_add_backend(AP_RangeFinder_PulsedLightLRF::detect(i, state[instance], params[instance], _type),
instance)) {
break;
}
}
break;
#endif
#if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED
case Type::MBI2C: {
uint8_t addr = AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR;
if (params[instance].address != 0) {
addr = params[instance].address;
}
probe_i2c_buses(instance, addr, AP_RangeFinder_MaxsonarI2CXL::detect);
break;
}
#endif
#if AP_RANGEFINDER_LWI2C_ENABLED
case Type::LWI2C:
if (params[instance].address) {
// the LW20 needs a long time to boot up, so we delay 1.5s here
#ifndef HAL_BUILD_AP_PERIPH
if (!hal.util->was_watchdog_armed()) {
hal.scheduler->delay(1500);
}
#endif
#ifdef HAL_RANGEFINDER_LIGHTWARE_I2C_BUS
auto *device_ptr = hal.i2c_mgr->get_device_ptr(HAL_RANGEFINDER_LIGHTWARE_I2C_BUS, params[instance].address);
if (device_ptr) {
_add_backend(AP_RangeFinder_LightWareI2C::detect(state[instance], params[instance],
*device_ptr),
instance);
}
#else
probe_i2c_buses(instance, params[instance].address, AP_RangeFinder_LightWareI2C::detect);
#endif
}
break;
#endif // AP_RANGEFINDER_LWI2C_ENABLED
#if AP_RANGEFINDER_TRI2C_ENABLED
case Type::TRI2C:
if (params[instance].address) {
probe_i2c_buses(instance, params[instance].address, AP_RangeFinder_TeraRangerI2C::detect);
}
break;
#endif
case Type::VL53L0X:
case Type::VL53L1X_Short:
FOREACH_I2C(i) {
#if AP_RANGEFINDER_VL53L0X_ENABLED
if (_add_backend(AP_RangeFinder_VL53L0X::detect(state[instance], params[instance],
hal.i2c_mgr->get_device(i, params[instance].address)),
instance)) {
break;
}
#endif
#if AP_RANGEFINDER_VL53L1X_ENABLED
if (_add_backend(AP_RangeFinder_VL53L1X::detect(state[instance], params[instance],
hal.i2c_mgr->get_device(i, params[instance].address),
_type == Type::VL53L1X_Short ? AP_RangeFinder_VL53L1X::DistanceMode::Short :
AP_RangeFinder_VL53L1X::DistanceMode::Long),
instance)) {
break;
}
#endif
}
break;
#if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED
case Type::BenewakeTFminiPlus: {
uint8_t addr = TFMINIPLUS_ADDR_DEFAULT;
if (params[instance].address != 0) {
addr = params[instance].address;
}
probe_i2c_buses(instance, addr, AP_RangeFinder_Benewake_TFMiniPlus::detect);
break;
}
#endif
#if AP_RANGEFINDER_BENEWAKE_TFS20L_ENABLED
case Type::BenewakeTFS20L: {
uint8_t addr = TFS20L_ADDR_DEFAULT;
if (params[instance].address != 0) {
addr = params[instance].address;
}
probe_i2c_buses(instance, addr, AP_RangeFinder_Benewake_TFS20L::detect);
break;
}
#endif
#if AP_RANGEFINDER_PWM_ENABLED
case Type::PX4_PWM:
// to ease moving from PX4 to ChibiOS we'll lie a little about
// the backend driver...
if (AP_RangeFinder_PWM::detect()) {
_add_backend(NEW_NOTHROW AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance);
}
break;
#endif
#if AP_RANGEFINDER_BBB_PRU_ENABLED
case Type::BBB_PRU:
if (AP_RangeFinder_BBB_PRU::detect()) {
_add_backend(NEW_NOTHROW AP_RangeFinder_BBB_PRU(state[instance], params[instance]), instance);
}
break;
#endif
#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED
case Type::LWSER:
serial_create_fn = AP_RangeFinder_LightWareSerial::create;
break;
#endif
#if AP_RANGEFINDER_LEDDARONE_ENABLED
case Type::LEDDARONE:
serial_create_fn = AP_RangeFinder_LeddarOne::create;
break;
#endif
#if AP_RANGEFINDER_USD1_SERIAL_ENABLED
case Type::USD1_Serial:
serial_create_fn = AP_RangeFinder_USD1_Serial::create;
break;
#endif
#if AP_RANGEFINDER_BEBOP_ENABLED
case Type::BEBOP:
if (AP_RangeFinder_Bebop::detect()) {
_add_backend(NEW_NOTHROW AP_RangeFinder_Bebop(state[instance], params[instance]), instance);
}
break;
#endif
#if AP_RANGEFINDER_MAVLINK_ENABLED
case Type::MAVLink:
if (AP_RangeFinder_MAVLink::detect()) {
_add_backend(NEW_NOTHROW AP_RangeFinder_MAVLink(state[instance], params[instance]), instance);
}
break;
#endif
#if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED
case Type::MBSER:
serial_create_fn = AP_RangeFinder_MaxsonarSerialLV::create;
break;
#endif
#if AP_RANGEFINDER_ANALOG_ENABLED
case Type::ANALOG:
// note that analog will always come back as present if the pin is valid
if (AP_RangeFinder_analog::detect(params[instance])) {
_add_backend(NEW_NOTHROW AP_RangeFinder_analog(state[instance], params[instance]), instance);
}
break;
#endif
#if AP_RANGEFINDER_HC_SR04_ENABLED
case Type::HC_SR04:
// note that this will always come back as present if the pin is valid
if (AP_RangeFinder_HC_SR04::detect(params[instance])) {
_add_backend(NEW_NOTHROW AP_RangeFinder_HC_SR04(state[instance], params[instance]), instance);
}
break;
#endif
#if AP_RANGEFINDER_NMEA_ENABLED
case Type::NMEA:
serial_create_fn = AP_RangeFinder_NMEA::create;
break;
#endif
#if AP_RANGEFINDER_WASP_ENABLED
case Type::WASP:
serial_create_fn = AP_RangeFinder_Wasp::create;
break;
#endif
#if AP_RANGEFINDER_BENEWAKE_TF02_ENABLED
case Type::BenewakeTF02:
serial_create_fn = AP_RangeFinder_Benewake_TF02::create;
break;
#endif
#if AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED
case Type::BenewakeTFmini:
serial_create_fn = AP_RangeFinder_Benewake_TFMini::create;
break;
#endif
#if AP_RANGEFINDER_BENEWAKE_TF03_ENABLED
case Type::BenewakeTF03:
serial_create_fn = AP_RangeFinder_Benewake_TF03::create;
break;
#endif
#if AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED
case Type::TeraRanger_Serial:
serial_create_fn = AP_RangeFinder_TeraRanger_Serial::create;
break;
#endif
#if AP_RANGEFINDER_PWM_ENABLED
case Type::PWM:
if (AP_RangeFinder_PWM::detect()) {
_add_backend(NEW_NOTHROW AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance);
}
break;
#endif
#if AP_RANGEFINDER_BLPING_ENABLED
case Type::BLPing:
serial_create_fn = AP_RangeFinder_BLPing::create;
break;
#endif
#if AP_RANGEFINDER_LANBAO_ENABLED
case Type::Lanbao:
serial_create_fn = AP_RangeFinder_Lanbao::create;
break;
#endif
#if AP_RANGEFINDER_LEDDARVU8_ENABLED
case Type::LeddarVu8_Serial:
serial_create_fn = AP_RangeFinder_LeddarVu8::create;
break;
#endif
#if AP_RANGEFINDER_DRONECAN_ENABLED
case Type::UAVCAN:
/*
the UAVCAN driver gets created when we first receive a
measurement. We take the instance slot now, even if we don't
yet have the driver
*/
num_instances = MAX(num_instances, instance+1);
break;
#endif
#if AP_RANGEFINDER_GYUS42V2_ENABLED
case Type::GYUS42v2:
serial_create_fn = AP_RangeFinder_GYUS42v2::create;
break;
#endif
#if AP_RANGEFINDER_SIM_ENABLED
case Type::SIM:
_add_backend(NEW_NOTHROW AP_RangeFinder_SITL(state[instance], params[instance], instance), instance);
break;
#endif
#if HAL_MSP_RANGEFINDER_ENABLED
case Type::MSP:
if (AP_RangeFinder_MSP::detect()) {
_add_backend(NEW_NOTHROW AP_RangeFinder_MSP(state[instance], params[instance]), instance);
}
break;
#endif // HAL_MSP_RANGEFINDER_ENABLED
#if AP_RANGEFINDER_USD1_CAN_ENABLED
case Type::USD1_CAN:
_add_backend(NEW_NOTHROW AP_RangeFinder_USD1_CAN(state[instance], params[instance]), instance);
break;
#endif
#if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED
case Type::Benewake_CAN:
_add_backend(NEW_NOTHROW AP_RangeFinder_Benewake_CAN(state[instance], params[instance]), instance);
break;
#endif
#if AP_RANGEFINDER_LUA_ENABLED
case Type::Lua_Scripting:
_add_backend(NEW_NOTHROW AP_RangeFinder_Lua(state[instance], params[instance]), instance);
break;
#endif
#if AP_RANGEFINDER_NOOPLOOP_ENABLED
case Type::NoopLoop_P:
serial_create_fn = AP_RangeFinder_NoopLoop::create;
break;
#endif
#if AP_RANGEFINDER_AINSTEIN_LR_D1_ENABLED
case Type::Ainstein_LR_D1:
serial_create_fn = AP_RangeFinder_Ainstein_LR_D1::create;
break;
#endif
#if AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED
case Type::TOFSenseP_CAN:
_add_backend(NEW_NOTHROW AP_RangeFinder_TOFSenseP_CAN(state[instance], params[instance]), instance);
break;
#endif
#if AP_RANGEFINDER_NRA24_CAN_DRIVER_ENABLED
#if AP_RANGEFINDER_NRA24_CAN_ENABLED
case Type::NRA24_CAN:
#endif
#if AP_RANGEFINDER_HEXSOONRADAR_ENABLED
case Type::HEXSOON_RADAR:
#endif
_add_backend(NEW_NOTHROW AP_RangeFinder_NRA24_CAN(state[instance], params[instance]), instance);
break;
#endif // AP_RANGEFINDER_NRA24_CAN_DRIVER_ENABLED
#if AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED
case Type::TOFSenseF_I2C: {
uint8_t addr = TOFSENSEP_I2C_DEFAULT_ADDR;
if (params[instance].address != 0) {
addr = params[instance].address;
}
FOREACH_I2C(i) {
if (_add_backend(AP_RangeFinder_TOFSenseF_I2C::detect(state[instance], params[instance],
hal.i2c_mgr->get_device(i, addr)),
instance)) {
break;
}
}
break;
}
#endif
#if AP_RANGEFINDER_JRE_SERIAL_ENABLED
case Type::JRE_Serial:
serial_create_fn = AP_RangeFinder_JRE_Serial::create;
break;
#endif
#if AP_RANGEFINDER_RDS02UF_ENABLED
case Type::RDS02UF:
serial_create_fn = AP_RangeFinder_RDS02UF::create;
break;
#endif
#if AP_RANGEFINDER_LIGHTWARE_GRF_ENABLED
case Type::LightWare_GRF:
serial_create_fn = AP_RangeFinder_LightWareGRF::create;
break;
#endif // AP_RANGEFINDER_LIGHTWARE_GRF_ENABLED
#if AP_RANGEFINDER_DTS6012M_ENABLED
case Type::DTS6012M:
serial_create_fn = AP_RangeFinder_DTS6012M::create;
break;
#endif // AP_RANGEFINDER_DTS6012M_ENABLED
case Type::NONE:
break;
}
if (serial_create_fn != nullptr) {
if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance)) {
auto *b = serial_create_fn(state[instance], params[instance]);
if (b != nullptr) {
_add_backend(b, instance, serial_instance++);
}
}
}
// if the backend has some local parameters then make those available in the tree
if (drivers[instance] && state[instance].var_info) {
backend_var_info[instance] = state[instance].var_info;
AP_Param::load_object_from_eeprom(drivers[instance], backend_var_info[instance]);
// param count could have changed
AP_Param::invalidate_count();
}
}
AP_RangeFinder_Backend *RangeFinder::get_backend(uint8_t id) const {
if (id >= num_instances) {
return nullptr;
}
if (drivers[id] != nullptr) {
if (drivers[id]->type() == Type::NONE) {
// pretend it isn't here; disabled at runtime?
return nullptr;
}
}
return drivers[id];
};
RangeFinder::Status RangeFinder::status_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return Status::NotConnected;
}
return backend->status();
}
void RangeFinder::handle_msg(const mavlink_message_t &msg)
{
uint8_t i;
for (i=0; i<num_instances; i++) {
if ((drivers[i] != nullptr) && ((Type)params[i].type.get() != Type::NONE)) {
drivers[i]->handle_msg(msg);
}
}
}
#if HAL_MSP_RANGEFINDER_ENABLED
void RangeFinder::handle_msp(const MSP::msp_rangefinder_data_message_t &pkt)
{
uint8_t i;
for (i=0; i<num_instances; i++) {
if ((drivers[i] != nullptr) && ((Type)params[i].type.get() == Type::MSP)) {
drivers[i]->handle_msp(pkt);
}
}
}
#endif // HAL_MSP_RANGEFINDER_ENABLED
// return true if we have a range finder with the specified orientation
bool RangeFinder::has_orientation(enum Rotation orientation) const
{
if ((find_instance(orientation) != nullptr)) {
// we have a rangefinder with this orientation
return true;
}
// special case for DroneCAN
// DroneCAN rangefinder backend is not created until we receive a
// measurement, so we need to check the params directly
#if AP_RANGEFINDER_DRONECAN_ENABLED
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
if ((RangeFinder::Type)params[i].type.get() == RangeFinder::Type::UAVCAN) {
if (params[i].orientation.get() == orientation) {
return true;
}
}
}
#endif
// no rangefinder with this orientation
return false;
}
// find first range finder instance with the specified orientation
AP_RangeFinder_Backend *RangeFinder::find_instance(enum Rotation orientation) const
{
// first try for a rangefinder that is in range
for (uint8_t i=0; i<num_instances; i++) {
AP_RangeFinder_Backend *backend = get_backend(i);
if (backend != nullptr &&
backend->orientation() == orientation &&
backend->status() == Status::Good) {
return backend;
}
}
// if none in range then return first with correct orientation
for (uint8_t i=0; i<num_instances; i++) {
AP_RangeFinder_Backend *backend = get_backend(i);
if (backend != nullptr &&
backend->orientation() == orientation) {
return backend;
}
}
return nullptr;
}
float RangeFinder::distance_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return 0;
}
return backend->distance();
}
int8_t RangeFinder::signal_quality_pct_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return RangeFinder::SIGNAL_QUALITY_UNKNOWN;
}
return backend->signal_quality_pct();
}
float RangeFinder::min_distance_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return 0; // consider NaN
}
return backend->min_distance();
}
float RangeFinder::max_distance_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return 0; // consider NaN
}
return backend->max_distance();
}
float RangeFinder::ground_clearance_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return 0; // consider NaN
}
return backend->ground_clearance();
}
bool RangeFinder::has_data_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return false;
}
return backend->has_data();
}
uint8_t RangeFinder::range_valid_count_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return 0;
}
return backend->range_valid_count();
}
const Vector3f &RangeFinder::get_pos_offset_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return pos_offset_zero;
}
return backend->get_pos_offset();
}
uint32_t RangeFinder::last_reading_ms(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return 0;
}
return backend->last_reading_ms();
}
MAV_DISTANCE_SENSOR RangeFinder::get_mav_distance_sensor_type_orient(enum Rotation orientation) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return MAV_DISTANCE_SENSOR_UNKNOWN;
}
return backend->get_mav_distance_sensor_type();
}
// get temperature reading in C. returns true on success and populates temp argument
bool RangeFinder::get_temp(enum Rotation orientation, float &temp) const
{
AP_RangeFinder_Backend *backend = find_instance(orientation);
if (backend == nullptr) {
return false;
}
return backend->get_temp(temp);
}
#if HAL_LOGGING_ENABLED
// Write an RFND (rangefinder) packet
void RangeFinder::Log_RFND() const
{
if (_log_rfnd_bit == uint32_t(-1)) {
return;
}
AP_Logger &logger = AP::logger();
if (!logger.should_log(_log_rfnd_bit)) {
return;
}
for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
const AP_RangeFinder_Backend *s = get_backend(i);
if (s == nullptr) {
continue;
}
const struct log_RFND pkt = {
LOG_PACKET_HEADER_INIT(LOG_RFND_MSG),
time_us : AP_HAL::micros64(),
instance : i,
dist : s->distance(),
status : (uint8_t)s->status(),
orient : s->orientation(),
quality : s->signal_quality_pct(),
};
AP::logger().WriteBlock(&pkt, sizeof(pkt));
}
}
#endif // HAL_LOGGING_ENABLED
bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_len) const
{
for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
if ((Type)params[i].type.get() == Type::NONE) {
continue;
}
if (drivers[i] == nullptr) {
hal.util->snprintf(failure_msg, failure_msg_len, "Rangefinder %X: Not Detected", i + 1);
return false;
}
// backend-specific checks. This might end up drivers[i]->arming_checks(...).
switch (drivers[i]->allocated_type()) {
#if AP_RANGEFINDER_ANALOG_ENABLED || AP_RANGEFINDER_PWM_ENABLED
#if AP_RANGEFINDER_ANALOG_ENABLED
case Type::ANALOG:
#endif
#if AP_RANGEFINDER_PWM_ENABLED
case Type::PX4_PWM:
case Type::PWM:
#endif
{
// ensure pin is configured
if (params[i].pin == -1) {
hal.util->snprintf(failure_msg, failure_msg_len, "RNGFND%u_PIN not set", unsigned(i + 1));
return false;
}
#if AP_RANGEFINDER_ANALOG_ENABLED
if (drivers[i]->allocated_type() == Type::ANALOG) {
// Analog backend does not use GPIO pin
break;
}
#endif
// ensure that the pin we're configured to use is available
if (!hal.gpio->valid_pin(params[i].pin)) {
uint8_t servo_ch;
if (hal.gpio->pin_to_servo_channel(params[i].pin, servo_ch)) {
hal.util->snprintf(failure_msg, failure_msg_len, "RNGFND%u_PIN=%d, set SERVO%u_FUNCTION=-1", unsigned(i + 1), int(params[i].pin.get()), unsigned(servo_ch+1));
} else {
hal.util->snprintf(failure_msg, failure_msg_len, "RNGFND%u_PIN=%d invalid", unsigned(i + 1), int(params[i].pin.get()));
}
return false;
}
break;
}
#endif // AP_RANGEFINDER_ANALOG_ENABLED || AP_RANGEFINDER_PWM_ENABLED
#if AP_RANGEFINDER_NRA24_CAN_DRIVER_ENABLED
#if AP_RANGEFINDER_NRA24_CAN_ENABLED
case Type::NRA24_CAN:
#endif
#if AP_RANGEFINDER_HEXSOONRADAR_ENABLED
case Type::HEXSOON_RADAR:
#endif
{
if (drivers[i]->status() == Status::NoData) {
// This sensor stops sending data if there is no relative motion. This will mostly happen during takeoff, before arming
// To avoid pre-arm failure, return true even though there is no data.
// This sensor also sends a "heartbeat" so we can differentiate between "NoData" and "NotConnected"
return true;
}
break;
}
#endif // AP_RANGEFINDER_NRA24_CAN_DRIVER_ENABLED
default:
break;
}
switch (drivers[i]->status()) {
case Status::NoData:
hal.util->snprintf(failure_msg, failure_msg_len, "Rangefinder %X: No Data", i + 1);
return false;
case Status::NotConnected:
hal.util->snprintf(failure_msg, failure_msg_len, "Rangefinder %X: Not Connected", i + 1);
return false;
case Status::OutOfRangeLow:
case Status::OutOfRangeHigh:
case Status::Good:
break;
}
}
return true;
}
RangeFinder *RangeFinder::_singleton;
namespace AP {
RangeFinder *rangefinder()
{
return RangeFinder::get_singleton();
}
}
#endif // AP_RANGEFINDER_ENABLED