21
21
#include < AP_HAL/utility/Socket_native.h>
22
22
#include " SITL_State_common.h"
23
23
24
+ #include < SITL/SIM_RF_Ainstein_LR_D1.h>
25
+ #include < SITL/SIM_RF_Benewake_TF02.h>
26
+ #include < SITL/SIM_RF_Benewake_TF03.h>
27
+ #include < SITL/SIM_RF_Benewake_TFmini.h>
28
+ #include < SITL/SIM_RF_BLping.h>
29
+ #include < SITL/SIM_RF_GYUS42v2.h>
30
+ #include < SITL/SIM_RF_JRE.h>
31
+ #include < SITL/SIM_RF_Lanbao.h>
32
+ #include < SITL/SIM_RF_LeddarOne.h>
33
+ #include < SITL/SIM_RF_LightWareSerialBinary.h>
34
+ #include < SITL/SIM_RF_LightWareSerial.h>
35
+ #include < SITL/SIM_RF_MAVLink.h>
36
+ #include < SITL/SIM_RF_MaxsonarSerialLV.h>
37
+ #include < SITL/SIM_RF_NMEA.h>
38
+ #include < SITL/SIM_RF_NoopLoop.h>
39
+ #include < SITL/SIM_RF_RDS02UF.h>
40
+ #include < SITL/SIM_RF_TeraRanger_Serial.h>
41
+ #include < SITL/SIM_RF_USD1_v0.h>
42
+ #include < SITL/SIM_RF_USD1_v1.h>
43
+ #include < SITL/SIM_RF_Wasp.h>
44
+
24
45
using namespace HALSITL ;
25
46
26
47
static const struct {
27
48
const char *name;
28
49
SITL::SerialRangeFinder *(*createfn)();
29
50
} serial_rangefinder_definitions[] {
51
+ { " ainsteinlrd1" , SITL::RF_Ainstein_LR_D1::create },
52
+ { " benewake_tf02" , SITL::RF_Benewake_TF02::create },
53
+ { " benewake_tf03" , SITL::RF_Benewake_TF03::create },
54
+ { " benewake_tfmini" , SITL::RF_Benewake_TFmini::create },
55
+ { " blping" , SITL::RF_BLping::create },
56
+ { " gyus42v2" , SITL::RF_GYUS42v2::create },
57
+ { " jre" , SITL::RF_JRE::create },
58
+ { " lanbao" , SITL::RF_Lanbao::create },
59
+ { " leddarone" , SITL::RF_LeddarOne::create },
60
+ { " leddarone" , SITL::RF_LeddarOne::create },
61
+ { " lightwareserial-binary" , SITL::RF_LightWareSerialBinary::create },
62
+ { " lightwareserial" , SITL::RF_LightWareSerial::create },
63
+ { " maxsonarseriallv" , SITL::RF_MaxsonarSerialLV::create },
64
+ { " nmea" , SITL::RF_NMEA::create },
65
+ { " nmea" , SITL::RF_NMEA::create },
66
+ { " nooploop_tofsense" , SITL::RF_Nooploop::create },
67
+ { " rds02uf" , SITL::RF_RDS02UF::create },
68
+ #if !defined(HAL_BUILD_AP_PERIPH)
69
+ { " rf_mavlink" , SITL::RF_MAVLink::create },
70
+ #endif
71
+ { " teraranger_serial" , SITL::RF_TeraRanger_Serial::create },
72
+ { " USD1_v0" , SITL::RF_USD1_v0::create },
73
+ { " USD1_v1" , SITL::RF_USD1_v1::create },
74
+ { " wasp" , SITL::RF_Wasp::create },
30
75
};
31
76
32
77
#define streq (a, b ) (!strcmp(a, b))
@@ -43,12 +88,8 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
43
88
return serial_rangefinders[num_serial_rangefinders++];
44
89
}
45
90
46
- if (streq (name, " benewake_tf02" )) {
47
- if (benewake_tf02 != nullptr ) {
48
- AP_HAL::panic (" Only one benewake_tf02 at a time" );
49
- }
50
- benewake_tf02 = NEW_NOTHROW SITL::RF_Benewake_TF02 ();
51
- return benewake_tf02;
91
+ if (false ) {
92
+ // this is an empty clause to ease else-if syntax
52
93
#if !defined(HAL_BUILD_AP_PERIPH)
53
94
} else if (streq (name, " vicon" )) {
54
95
if (vicon != nullptr ) {
@@ -67,111 +108,6 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
67
108
}
68
109
sitl_model->set_adsb (adsb);
69
110
return adsb;
70
- #endif
71
- } else if (streq (name, " ainsteinlrd1" )) {
72
- if (ainsteinlrd1 != nullptr ) {
73
- AP_HAL::panic (" Only one ainsteinlrd1 at a time" );
74
- }
75
- ainsteinlrd1 = NEW_NOTHROW SITL::RF_Ainstein_LR_D1 ();
76
- return ainsteinlrd1;
77
- } else if (streq (name, " benewake_tf03" )) {
78
- if (benewake_tf03 != nullptr ) {
79
- AP_HAL::panic (" Only one benewake_tf03 at a time" );
80
- }
81
- benewake_tf03 = NEW_NOTHROW SITL::RF_Benewake_TF03 ();
82
- return benewake_tf03;
83
- } else if (streq (name, " benewake_tfmini" )) {
84
- if (benewake_tfmini != nullptr ) {
85
- AP_HAL::panic (" Only one benewake_tfmini at a time" );
86
- }
87
- benewake_tfmini = NEW_NOTHROW SITL::RF_Benewake_TFmini ();
88
- return benewake_tfmini;
89
- } else if (streq (name, " nooploop_tofsense" )) {
90
- if (nooploop != nullptr ) {
91
- AP_HAL::panic (" Only one nooploop_tofsense at a time" );
92
- }
93
- nooploop = NEW_NOTHROW SITL::RF_Nooploop ();
94
- return nooploop;
95
- } else if (streq (name, " teraranger_serial" )) {
96
- if (teraranger_serial != nullptr ) {
97
- AP_HAL::panic (" Only one teraranger_serial at a time" );
98
- }
99
- teraranger_serial = NEW_NOTHROW SITL::RF_TeraRanger_Serial ();
100
- return teraranger_serial;
101
- } else if (streq (name, " lightwareserial" )) {
102
- if (lightwareserial != nullptr ) {
103
- AP_HAL::panic (" Only one lightwareserial at a time" );
104
- }
105
- lightwareserial = NEW_NOTHROW SITL::RF_LightWareSerial ();
106
- return lightwareserial;
107
- } else if (streq (name, " lightwareserial-binary" )) {
108
- if (lightwareserial_binary != nullptr ) {
109
- AP_HAL::panic (" Only one lightwareserial-binary at a time" );
110
- }
111
- lightwareserial_binary = NEW_NOTHROW SITL::RF_LightWareSerialBinary ();
112
- return lightwareserial_binary;
113
- } else if (streq (name, " lanbao" )) {
114
- if (lanbao != nullptr ) {
115
- AP_HAL::panic (" Only one lanbao at a time" );
116
- }
117
- lanbao = NEW_NOTHROW SITL::RF_Lanbao ();
118
- return lanbao;
119
- } else if (streq (name, " blping" )) {
120
- if (blping != nullptr ) {
121
- AP_HAL::panic (" Only one blping at a time" );
122
- }
123
- blping = NEW_NOTHROW SITL::RF_BLping ();
124
- return blping;
125
- } else if (streq (name, " leddarone" )) {
126
- if (leddarone != nullptr ) {
127
- AP_HAL::panic (" Only one leddarone at a time" );
128
- }
129
- leddarone = NEW_NOTHROW SITL::RF_LeddarOne ();
130
- return leddarone;
131
- } else if (streq (name, " rds02uf" )) {
132
- if (rds02uf != nullptr ) {
133
- AP_HAL::panic (" Only one rds02uf at a time" );
134
- }
135
- rds02uf = NEW_NOTHROW SITL::RF_RDS02UF ();
136
- return rds02uf;
137
- } else if (streq (name, " USD1_v0" )) {
138
- if (USD1_v0 != nullptr ) {
139
- AP_HAL::panic (" Only one USD1_v0 at a time" );
140
- }
141
- USD1_v0 = NEW_NOTHROW SITL::RF_USD1_v0 ();
142
- return USD1_v0;
143
- } else if (streq (name, " USD1_v1" )) {
144
- if (USD1_v1 != nullptr ) {
145
- AP_HAL::panic (" Only one USD1_v1 at a time" );
146
- }
147
- USD1_v1 = NEW_NOTHROW SITL::RF_USD1_v1 ();
148
- return USD1_v1;
149
- } else if (streq (name, " maxsonarseriallv" )) {
150
- if (maxsonarseriallv != nullptr ) {
151
- AP_HAL::panic (" Only one maxsonarseriallv at a time" );
152
- }
153
- maxsonarseriallv = NEW_NOTHROW SITL::RF_MaxsonarSerialLV ();
154
- return maxsonarseriallv;
155
- } else if (streq (name, " wasp" )) {
156
- if (wasp != nullptr ) {
157
- AP_HAL::panic (" Only one wasp at a time" );
158
- }
159
- wasp = NEW_NOTHROW SITL::RF_Wasp ();
160
- return wasp;
161
- } else if (streq (name, " nmea" )) {
162
- if (nmea != nullptr ) {
163
- AP_HAL::panic (" Only one nmea at a time" );
164
- }
165
- nmea = NEW_NOTHROW SITL::RF_NMEA ();
166
- return nmea;
167
-
168
- #if !defined(HAL_BUILD_AP_PERIPH)
169
- } else if (streq (name, " rf_mavlink" )) {
170
- if (rf_mavlink != nullptr ) {
171
- AP_HAL::panic (" Only one rf_mavlink at a time" );
172
- }
173
- rf_mavlink = NEW_NOTHROW SITL::RF_MAVLink ();
174
- return rf_mavlink;
175
111
#endif
176
112
} else if (streq (name, " frsky-d" )) {
177
113
if (frsky_d != nullptr ) {
@@ -260,18 +196,6 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
260
196
sitl_model->set_ie24 (&_sitl->ie24_sim );
261
197
return &_sitl->ie24_sim ;
262
198
#endif // HAL_BUILD_AP_PERIPH
263
- } else if (streq (name, " jre" )) {
264
- if (jre != nullptr ) {
265
- AP_HAL::panic (" Only one jre at a time" );
266
- }
267
- jre = NEW_NOTHROW SITL::RF_JRE ();
268
- return jre;
269
- } else if (streq (name, " gyus42v2" )) {
270
- if (gyus42v2 != nullptr ) {
271
- AP_HAL::panic (" Only one gyus42v2 at a time" );
272
- }
273
- gyus42v2 = NEW_NOTHROW SITL::RF_GYUS42v2 ();
274
- return gyus42v2;
275
199
} else if (streq (name, " megasquirt" )) {
276
200
if (efi_ms != nullptr ) {
277
201
AP_HAL::panic (" Only one megasquirt at a time" );
@@ -364,66 +288,6 @@ void SITL_State_Common::sim_update(void)
364
288
attitude);
365
289
}
366
290
#endif
367
- if (ainsteinlrd1 != nullptr ) {
368
- ainsteinlrd1->update (sitl_model->rangefinder_range ());
369
- }
370
- if (benewake_tf02 != nullptr ) {
371
- benewake_tf02->update (sitl_model->rangefinder_range ());
372
- }
373
- if (benewake_tf03 != nullptr ) {
374
- benewake_tf03->update (sitl_model->rangefinder_range ());
375
- }
376
- if (benewake_tfmini != nullptr ) {
377
- benewake_tfmini->update (sitl_model->rangefinder_range ());
378
- }
379
- if (jre != nullptr ) {
380
- jre->update (sitl_model->rangefinder_range ());
381
- }
382
- if (nooploop != nullptr ) {
383
- nooploop->update (sitl_model->rangefinder_range ());
384
- }
385
- if (teraranger_serial != nullptr ) {
386
- teraranger_serial->update (sitl_model->rangefinder_range ());
387
- }
388
- if (lightwareserial != nullptr ) {
389
- lightwareserial->update (sitl_model->rangefinder_range ());
390
- }
391
- if (lightwareserial_binary != nullptr ) {
392
- lightwareserial_binary->update (sitl_model->rangefinder_range ());
393
- }
394
- if (lanbao != nullptr ) {
395
- lanbao->update (sitl_model->rangefinder_range ());
396
- }
397
- if (blping != nullptr ) {
398
- blping->update (sitl_model->rangefinder_range ());
399
- }
400
- if (leddarone != nullptr ) {
401
- leddarone->update (sitl_model->rangefinder_range ());
402
- }
403
- if (rds02uf != nullptr ) {
404
- rds02uf->update (sitl_model->rangefinder_range ());
405
- }
406
- if (USD1_v0 != nullptr ) {
407
- USD1_v0->update (sitl_model->rangefinder_range ());
408
- }
409
- if (USD1_v1 != nullptr ) {
410
- USD1_v1->update (sitl_model->rangefinder_range ());
411
- }
412
- if (maxsonarseriallv != nullptr ) {
413
- maxsonarseriallv->update (sitl_model->rangefinder_range ());
414
- }
415
- if (wasp != nullptr ) {
416
- wasp->update (sitl_model->rangefinder_range ());
417
- }
418
- if (nmea != nullptr ) {
419
- nmea->update (sitl_model->rangefinder_range ());
420
- }
421
- if (rf_mavlink != nullptr ) {
422
- rf_mavlink->update (sitl_model->rangefinder_range ());
423
- }
424
- if (gyus42v2 != nullptr ) {
425
- gyus42v2->update (sitl_model->rangefinder_range ());
426
- }
427
291
for (uint8_t i=0 ; i<num_serial_rangefinders; i++) {
428
292
serial_rangefinders[i]->update (sitl_model->rangefinder_range ());
429
293
}
0 commit comments