RangeFinder.cpp 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include "RangeFinder.h"
  14. #include "AP_RangeFinder_analog.h"
  15. #include "AP_RangeFinder_PulsedLightLRF.h"
  16. #include "AP_RangeFinder_MaxsonarI2CXL.h"
  17. #include "AP_RangeFinder_MaxsonarSerialLV.h"
  18. #include "AP_RangeFinder_BBB_PRU.h"
  19. #include "AP_RangeFinder_LightWareI2C.h"
  20. #include "AP_RangeFinder_LightWareSerial.h"
  21. #if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
  22. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && \
  23. defined(HAVE_LIBIIO)
  24. #include "AP_RangeFinder_Bebop.h"
  25. #endif
  26. #include "AP_RangeFinder_MAVLink.h"
  27. #include "AP_RangeFinder_LeddarOne.h"
  28. #include "AP_RangeFinder_uLanding.h"
  29. #include "AP_RangeFinder_TeraRangerI2C.h"
  30. #include "AP_RangeFinder_VL53L0X.h"
  31. #include "AP_RangeFinder_VL53L1X.h"
  32. #include "AP_RangeFinder_NMEA.h"
  33. #include "AP_RangeFinder_Wasp.h"
  34. #include "AP_RangeFinder_Benewake.h"
  35. #include "AP_RangeFinder_Benewake_TFMiniPlus.h"
  36. #include "AP_RangeFinder_PWM.h"
  37. #include "AP_RangeFinder_BLPing.h"
  38. #include "AP_RangeFinder_UAVCAN.h"
  39. #include "AP_RangeFinder_Lanbao.h"
  40. #include <AP_BoardConfig/AP_BoardConfig.h>
  41. #include <AP_Logger/AP_Logger.h>
  42. #include <AP_SerialManager/AP_SerialManager.h>
  43. #include <AP_Vehicle/AP_Vehicle_Type.h>
  44. extern const AP_HAL::HAL &hal;
  45. // table of user settable parameters
  46. const AP_Param::GroupInfo RangeFinder::var_info[] = {
  47. // @Group: 1_
  48. // @Path: AP_RangeFinder_Params.cpp
  49. AP_SUBGROUPINFO(params[0], "1_", 25, RangeFinder, AP_RangeFinder_Params),
  50. // @Group: 1_
  51. // @Path: AP_RangeFinder_Wasp.cpp
  52. AP_SUBGROUPVARPTR(drivers[0], "1_", 57, RangeFinder, backend_var_info[0]),
  53. #if RANGEFINDER_MAX_INSTANCES > 1
  54. // @Group: 2_
  55. // @Path: AP_RangeFinder_Params.cpp
  56. AP_SUBGROUPINFO(params[1], "2_", 27, RangeFinder, AP_RangeFinder_Params),
  57. // @Group: 2_
  58. // @Path: AP_RangeFinder_Wasp.cpp
  59. AP_SUBGROUPVARPTR(drivers[1], "2_", 58, RangeFinder, backend_var_info[1]),
  60. #endif
  61. #if RANGEFINDER_MAX_INSTANCES > 2
  62. // @Group: 3_
  63. // @Path: AP_RangeFinder_Params.cpp
  64. AP_SUBGROUPINFO(params[2], "3_", 29, RangeFinder, AP_RangeFinder_Params),
  65. // @Group: 3_
  66. // @Path: AP_RangeFinder_Wasp.cpp
  67. AP_SUBGROUPVARPTR(drivers[2], "3_", 59, RangeFinder, backend_var_info[2]),
  68. #endif
  69. #if RANGEFINDER_MAX_INSTANCES > 3
  70. // @Group: 4_
  71. // @Path: AP_RangeFinder_Params.cpp
  72. AP_SUBGROUPINFO(params[3], "4_", 31, RangeFinder, AP_RangeFinder_Params),
  73. // @Group: 4_
  74. // @Path: AP_RangeFinder_Wasp.cpp
  75. AP_SUBGROUPVARPTR(drivers[0], "4_", 60, RangeFinder, backend_var_info[3]),
  76. #endif
  77. #if RANGEFINDER_MAX_INSTANCES > 4
  78. // @Group: 5_
  79. // @Path: AP_RangeFinder_Params.cpp
  80. AP_SUBGROUPINFO(params[4], "5_", 33, RangeFinder, AP_RangeFinder_Params),
  81. // @Group: 5_
  82. // @Path: AP_RangeFinder_Wasp.cpp
  83. AP_SUBGROUPVARPTR(drivers[4], "5_", 34, RangeFinder, backend_var_info[4]),
  84. #endif
  85. #if RANGEFINDER_MAX_INSTANCES > 5
  86. // @Group: 6_
  87. // @Path: AP_RangeFinder_Params.cpp
  88. AP_SUBGROUPINFO(params[5], "6_", 35, RangeFinder, AP_RangeFinder_Params),
  89. // @Group: 6_
  90. // @Path: AP_RangeFinder_Wasp.cpp
  91. AP_SUBGROUPVARPTR(drivers[5], "6_", 36, RangeFinder, backend_var_info[5]),
  92. #endif
  93. #if RANGEFINDER_MAX_INSTANCES > 6
  94. // @Group: 7_
  95. // @Path: AP_RangeFinder_Params.cpp
  96. AP_SUBGROUPINFO(params[6], "7_", 37, RangeFinder, AP_RangeFinder_Params),
  97. // @Group: 7_
  98. // @Path: AP_RangeFinder_Wasp.cpp
  99. AP_SUBGROUPVARPTR(drivers[6], "7_", 38, RangeFinder, backend_var_info[6]),
  100. #endif
  101. #if RANGEFINDER_MAX_INSTANCES > 7
  102. // @Group: 8_
  103. // @Path: AP_RangeFinder_Params.cpp
  104. AP_SUBGROUPINFO(params[7], "8_", 39, RangeFinder, AP_RangeFinder_Params),
  105. // @Group: 8_
  106. // @Path: AP_RangeFinder_Wasp.cpp
  107. AP_SUBGROUPVARPTR(drivers[7], "8_", 40, RangeFinder, backend_var_info[7]),
  108. #endif
  109. #if RANGEFINDER_MAX_INSTANCES > 8
  110. // @Group: 9_
  111. // @Path: AP_RangeFinder_Params.cpp
  112. AP_SUBGROUPINFO(params[8], "9_", 41, RangeFinder, AP_RangeFinder_Params),
  113. // @Group: 9_
  114. // @Path: AP_RangeFinder_Wasp.cpp
  115. AP_SUBGROUPVARPTR(drivers[8], "9_", 42, RangeFinder, backend_var_info[8]),
  116. #endif
  117. #if RANGEFINDER_MAX_INSTANCES > 9
  118. // @Group: A_
  119. // @Path: AP_RangeFinder_Params.cpp
  120. AP_SUBGROUPINFO(params[9], "A_", 43, RangeFinder, AP_RangeFinder_Params),
  121. // @Group: A_
  122. // @Path: AP_RangeFinder_Wasp.cpp
  123. AP_SUBGROUPVARPTR(drivers[9], "A_", 44, RangeFinder, backend_var_info[9]),
  124. #endif
  125. AP_GROUPEND
  126. };
  127. const AP_Param::GroupInfo *RangeFinder::backend_var_info[RANGEFINDER_MAX_INSTANCES];
  128. RangeFinder::RangeFinder()
  129. {
  130. AP_Param::setup_object_defaults(this, var_info);
  131. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  132. if (_singleton != nullptr) {
  133. AP_HAL::panic("Rangefinder must be singleton");
  134. }
  135. #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
  136. _singleton = this;
  137. }
  138. void RangeFinder::convert_params(void) {
  139. if (params[0].type.configured_in_storage()) {
  140. // _params[0]._type will always be configured in storage after conversion is done the first time
  141. return;
  142. }
  143. struct ConversionTable {
  144. uint8_t old_element;
  145. uint8_t new_index;
  146. uint8_t instance;
  147. };
  148. const struct ConversionTable conversionTable[] = {
  149. {0, 0, 0}, //0, TYPE 1
  150. {1, 1, 0}, //1, PIN 1
  151. {2, 2, 0}, //2, SCALING 1
  152. {3, 3, 0}, //3, OFFSET 1
  153. {4, 4, 0}, //4, FUNCTION 1
  154. {5, 5, 0}, //5, MIN_CM 1
  155. {6, 6, 0}, //6, MAX_CM 1
  156. {7, 7, 0}, //7, STOP_PIN 1
  157. {8, 8, 0}, //8, SETTLE 1
  158. {9, 9, 0}, //9, RMETRIC 1
  159. {10, 10, 0}, //10, PWRRNG 1 (previously existed only once for all sensors)
  160. {11, 11, 0}, //11, GNDCLEAR 1
  161. {23, 12, 0}, //23, ADDR 1
  162. {49, 13, 0}, //49, POS 1
  163. {53, 14, 0}, //53, ORIENT 1
  164. //{57, 1, 0}, //57, backend 1
  165. {12, 0, 1}, //12, TYPE 2
  166. {13, 1, 1}, //13, PIN 2
  167. {14, 2, 1}, //14, SCALING 2
  168. {15, 3, 1}, //15, OFFSET 2
  169. {16, 4, 1}, //16, FUNCTION 2
  170. {17, 5, 1}, //17, MIN_CM 2
  171. {18, 6, 1}, //18, MAX_CM 2
  172. {19, 7, 1}, //19, STOP_PIN 2
  173. {20, 8, 1}, //20, SETTLE 2
  174. {21, 9, 1}, //21, RMETRIC 2
  175. //{, 10, 1}, //PWRRNG 2 (previously existed only once for all sensors)
  176. {22, 11, 1}, //22, GNDCLEAR 2
  177. {24, 12, 1}, //24, ADDR 2
  178. {50, 13, 1}, //50, POS 2
  179. {54, 14, 1}, //54, ORIENT 2
  180. //{58, 3, 1}, //58, backend 2
  181. {25, 0, 2}, //25, TYPE 3
  182. {26, 1, 2}, //26, PIN 3
  183. {27, 2, 2}, //27, SCALING 3
  184. {28, 3, 2}, //28, OFFSET 3
  185. {29, 4, 2}, //29, FUNCTION 3
  186. {30, 5, 2}, //30, MIN_CM 3
  187. {31, 6, 2}, //31, MAX_CM 3
  188. {32, 7, 2}, //32, STOP_PIN 3
  189. {33, 8, 2}, //33, SETTLE 3
  190. {34, 9, 2}, //34, RMETRIC 3
  191. //{, 10, 2}, //PWRRNG 3 (previously existed only once for all sensors)
  192. {35, 11, 2}, //35, GNDCLEAR 3
  193. {36, 12, 2}, //36, ADDR 3
  194. {51, 13, 2}, //51, POS 3
  195. {55, 14, 2}, //55, ORIENT 3
  196. //{59, 5, 2}, //59, backend 3
  197. {37, 0, 3}, //37, TYPE 4
  198. {38, 1, 3}, //38, PIN 4
  199. {39, 2, 3}, //39, SCALING 4
  200. {40, 3, 3}, //40, OFFSET 4
  201. {41, 4, 3}, //41, FUNCTION 4
  202. {42, 5, 3}, //42, MIN_CM 4
  203. {43, 6, 3}, //43, MAX_CM 4
  204. {44, 7, 3}, //44, STOP_PIN 4
  205. {45, 8, 3}, //45, SETTLE 4
  206. {46, 9, 3}, //46, RMETRIC 4
  207. //{, 10, 3}, //PWRRNG 4 (previously existed only once for all sensors)
  208. {47, 11, 3}, //47, GNDCLEAR 4
  209. {48, 12, 3}, //48, ADDR 4
  210. {52, 13, 3}, //52, POS 4
  211. {56, 14, 3}, //56, ORIENT 4
  212. //{60, 7, 3}, //60, backend 4
  213. };
  214. char param_name[17] = {0};
  215. AP_Param::ConversionInfo info;
  216. info.new_name = param_name;
  217. #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  218. info.old_key = 71;
  219. #elif APM_BUILD_TYPE(APM_BUILD_ArduCopter)
  220. info.old_key = 53;
  221. #elif APM_BUILD_TYPE(APM_BUILD_ArduSub)
  222. info.old_key = 35;
  223. #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
  224. info.old_key = 197;
  225. #else
  226. params[0].type.save(true);
  227. return; // no conversion is supported on this platform
  228. #endif
  229. for (uint8_t i = 0; i < ARRAY_SIZE(conversionTable); i++) {
  230. uint8_t param_instance = conversionTable[i].instance + 1;
  231. uint8_t destination_index = conversionTable[i].new_index;
  232. info.old_group_element = conversionTable[i].old_element;
  233. info.type = (ap_var_type)AP_RangeFinder_Params::var_info[destination_index].type;
  234. hal.util->snprintf(param_name, sizeof(param_name), "RNGFND%X_%s", param_instance, AP_RangeFinder_Params::var_info[destination_index].name);
  235. param_name[sizeof(param_name)-1] = '\0';
  236. AP_Param::convert_old_parameter(&info, 1.0f, 0);
  237. }
  238. // force _params[0]._type into storage to flag that conversion has been done
  239. params[0].type.save(true);
  240. }
  241. /*
  242. initialise the RangeFinder class. We do detection of attached range
  243. finders here. For now we won't allow for hot-plugging of
  244. rangefinders.
  245. */
  246. void RangeFinder::init(enum Rotation orientation_default)
  247. {
  248. if (num_instances != 0) {
  249. // init called a 2nd time?
  250. return;
  251. }
  252. convert_params();
  253. // set orientation defaults
  254. for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
  255. params[i].orientation.set_default(orientation_default);
  256. }
  257. for (uint8_t i=0, serial_instance = 0; i<RANGEFINDER_MAX_INSTANCES; i++) {
  258. // serial_instance will be increased inside detect_instance
  259. // if a serial driver is loaded for this instance
  260. detect_instance(i, serial_instance);
  261. if (drivers[i] != nullptr) {
  262. // we loaded a driver for this instance, so it must be
  263. // present (although it may not be healthy)
  264. num_instances = i+1;
  265. }
  266. // initialise status
  267. state[i].status = RangeFinder_NotConnected;
  268. state[i].range_valid_count = 0;
  269. }
  270. }
  271. /*
  272. update RangeFinder state for all instances. This should be called at
  273. around 10Hz by main loop
  274. */
  275. void RangeFinder::update(void)
  276. {
  277. for (uint8_t i=0; i<num_instances; i++) {
  278. if (drivers[i] != nullptr) {
  279. if (params[i].type == RangeFinder_TYPE_NONE) {
  280. // allow user to disable a rangefinder at runtime
  281. state[i].status = RangeFinder_NotConnected;
  282. state[i].range_valid_count = 0;
  283. continue;
  284. }
  285. drivers[i]->update();
  286. }
  287. }
  288. Log_RFND();
  289. }
  290. bool RangeFinder::_add_backend(AP_RangeFinder_Backend *backend)
  291. {
  292. if (!backend) {
  293. return false;
  294. }
  295. if (num_instances == RANGEFINDER_MAX_INSTANCES) {
  296. AP_HAL::panic("Too many RANGERS backends");
  297. }
  298. drivers[num_instances++] = backend;
  299. return true;
  300. }
  301. /*
  302. detect if an instance of a rangefinder is connected.
  303. */
  304. void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
  305. {
  306. enum RangeFinder_Type _type = (enum RangeFinder_Type)params[instance].type.get();
  307. switch (_type) {
  308. case RangeFinder_TYPE_PLI2C:
  309. case RangeFinder_TYPE_PLI2CV3:
  310. case RangeFinder_TYPE_PLI2CV3HP:
  311. FOREACH_I2C(i) {
  312. if (_add_backend(AP_RangeFinder_PulsedLightLRF::detect(i, state[instance], params[instance], _type))) {
  313. break;
  314. }
  315. }
  316. break;
  317. case RangeFinder_TYPE_MBI2C:
  318. FOREACH_I2C(i) {
  319. if (_add_backend(AP_RangeFinder_MaxsonarI2CXL::detect(state[instance], params[instance],
  320. hal.i2c_mgr->get_device(i, AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR)))) {
  321. break;
  322. }
  323. }
  324. break;
  325. case RangeFinder_TYPE_LWI2C:
  326. if (params[instance].address) {
  327. // the LW20 needs a long time to boot up, so we delay 1.5s here
  328. if (!hal.util->was_watchdog_armed()) {
  329. hal.scheduler->delay(1500);
  330. }
  331. #ifdef HAL_RANGEFINDER_LIGHTWARE_I2C_BUS
  332. _add_backend(AP_RangeFinder_LightWareI2C::detect(state[instance], params[instance],
  333. hal.i2c_mgr->get_device(HAL_RANGEFINDER_LIGHTWARE_I2C_BUS, params[instance].address)));
  334. #else
  335. FOREACH_I2C(i) {
  336. if (_add_backend(AP_RangeFinder_LightWareI2C::detect(state[instance], params[instance],
  337. hal.i2c_mgr->get_device(i, params[instance].address)))) {
  338. break;
  339. }
  340. }
  341. #endif
  342. }
  343. break;
  344. case RangeFinder_TYPE_TRI2C:
  345. if (params[instance].address) {
  346. FOREACH_I2C(i) {
  347. if (_add_backend(AP_RangeFinder_TeraRangerI2C::detect(state[instance], params[instance],
  348. hal.i2c_mgr->get_device(i, params[instance].address)))) {
  349. break;
  350. }
  351. }
  352. }
  353. break;
  354. case RangeFinder_TYPE_VL53L0X:
  355. FOREACH_I2C(i) {
  356. if (_add_backend(AP_RangeFinder_VL53L0X::detect(state[instance], params[instance],
  357. hal.i2c_mgr->get_device(i, params[instance].address)))) {
  358. break;
  359. }
  360. if (_add_backend(AP_RangeFinder_VL53L1X::detect(state[instance], params[instance],
  361. hal.i2c_mgr->get_device(i, params[instance].address)))) {
  362. break;
  363. }
  364. }
  365. break;
  366. case RangeFinder_TYPE_BenewakeTFminiPlus:
  367. FOREACH_I2C(i) {
  368. if (_add_backend(AP_RangeFinder_Benewake_TFMiniPlus::detect(state[instance], params[instance],
  369. hal.i2c_mgr->get_device(i, params[instance].address)))) {
  370. break;
  371. }
  372. }
  373. break;
  374. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  375. case RangeFinder_TYPE_PX4_PWM:
  376. // to ease moving from PX4 to ChibiOS we'll lie a little about
  377. // the backend driver...
  378. if (AP_RangeFinder_PWM::detect()) {
  379. drivers[instance] = new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height);
  380. }
  381. break;
  382. #endif
  383. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI
  384. case RangeFinder_TYPE_BBB_PRU:
  385. if (AP_RangeFinder_BBB_PRU::detect()) {
  386. drivers[instance] = new AP_RangeFinder_BBB_PRU(state[instance], params[instance]);
  387. }
  388. break;
  389. #endif
  390. case RangeFinder_TYPE_LWSER:
  391. if (AP_RangeFinder_LightWareSerial::detect(serial_instance)) {
  392. drivers[instance] = new AP_RangeFinder_LightWareSerial(state[instance], params[instance], serial_instance++);
  393. }
  394. break;
  395. case RangeFinder_TYPE_LEDDARONE:
  396. if (AP_RangeFinder_LeddarOne::detect(serial_instance)) {
  397. drivers[instance] = new AP_RangeFinder_LeddarOne(state[instance], params[instance], serial_instance++);
  398. }
  399. break;
  400. case RangeFinder_TYPE_ULANDING:
  401. if (AP_RangeFinder_uLanding::detect(serial_instance)) {
  402. drivers[instance] = new AP_RangeFinder_uLanding(state[instance], params[instance], serial_instance++);
  403. }
  404. break;
  405. #if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
  406. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO)
  407. case RangeFinder_TYPE_BEBOP:
  408. if (AP_RangeFinder_Bebop::detect()) {
  409. drivers[instance] = new AP_RangeFinder_Bebop(state[instance], params[instance]);
  410. }
  411. break;
  412. #endif
  413. case RangeFinder_TYPE_MAVLink:
  414. if (AP_RangeFinder_MAVLink::detect()) {
  415. drivers[instance] = new AP_RangeFinder_MAVLink(state[instance], params[instance]);
  416. }
  417. break;
  418. case RangeFinder_TYPE_MBSER:
  419. if (AP_RangeFinder_MaxsonarSerialLV::detect(serial_instance)) {
  420. drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(state[instance], params[instance], serial_instance++);
  421. }
  422. break;
  423. case RangeFinder_TYPE_ANALOG:
  424. // note that analog will always come back as present if the pin is valid
  425. if (AP_RangeFinder_analog::detect(params[instance])) {
  426. drivers[instance] = new AP_RangeFinder_analog(state[instance], params[instance]);
  427. }
  428. break;
  429. case RangeFinder_TYPE_NMEA:
  430. if (AP_RangeFinder_NMEA::detect(serial_instance)) {
  431. drivers[instance] = new AP_RangeFinder_NMEA(state[instance], params[instance], serial_instance++);
  432. }
  433. break;
  434. case RangeFinder_TYPE_WASP:
  435. if (AP_RangeFinder_Wasp::detect(serial_instance)) {
  436. drivers[instance] = new AP_RangeFinder_Wasp(state[instance], params[instance], serial_instance++);
  437. }
  438. break;
  439. case RangeFinder_TYPE_BenewakeTF02:
  440. if (AP_RangeFinder_Benewake::detect(serial_instance)) {
  441. drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TF02);
  442. }
  443. break;
  444. case RangeFinder_TYPE_BenewakeTFmini:
  445. if (AP_RangeFinder_Benewake::detect(serial_instance)) {
  446. drivers[instance] = new AP_RangeFinder_Benewake(state[instance], params[instance], serial_instance++, AP_RangeFinder_Benewake::BENEWAKE_TFmini);
  447. }
  448. break;
  449. case RangeFinder_TYPE_PWM:
  450. if (AP_RangeFinder_PWM::detect()) {
  451. drivers[instance] = new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height);
  452. }
  453. break;
  454. case RangeFinder_TYPE_BLPing:
  455. if (AP_RangeFinder_BLPing::detect(serial_instance)) {
  456. drivers[instance] = new AP_RangeFinder_BLPing(state[instance], params[instance], serial_instance++);
  457. }
  458. break;
  459. case RangeFinder_TYPE_Lanbao:
  460. if (AP_RangeFinder_Lanbao::detect(serial_instance)) {
  461. drivers[instance] = new AP_RangeFinder_Lanbao(state[instance], params[instance], serial_instance++);
  462. }
  463. break;
  464. default:
  465. break;
  466. }
  467. // if the backend has some local parameters then make those available in the tree
  468. if (drivers[instance] && state[instance].var_info) {
  469. backend_var_info[instance] = state[instance].var_info;
  470. AP_Param::load_object_from_eeprom(drivers[instance], backend_var_info[instance]);
  471. }
  472. }
  473. AP_RangeFinder_Backend *RangeFinder::get_backend(uint8_t id) const {
  474. if (id >= num_instances) {
  475. return nullptr;
  476. }
  477. if (drivers[id] != nullptr) {
  478. if (drivers[id]->type() == RangeFinder_TYPE_NONE) {
  479. // pretend it isn't here; disabled at runtime?
  480. return nullptr;
  481. }
  482. }
  483. return drivers[id];
  484. };
  485. RangeFinder::RangeFinder_Status RangeFinder::status_orient(enum Rotation orientation) const
  486. {
  487. AP_RangeFinder_Backend *backend = find_instance(orientation);
  488. if (backend == nullptr) {
  489. return RangeFinder_NotConnected;
  490. }
  491. return backend->status();
  492. }
  493. void RangeFinder::handle_msg(const mavlink_message_t &msg)
  494. {
  495. uint8_t i;
  496. for (i=0; i<num_instances; i++) {
  497. if ((drivers[i] != nullptr) && (params[i].type != RangeFinder_TYPE_NONE)) {
  498. drivers[i]->handle_msg(msg);
  499. }
  500. }
  501. }
  502. // return true if we have a range finder with the specified orientation
  503. bool RangeFinder::has_orientation(enum Rotation orientation) const
  504. {
  505. return (find_instance(orientation) != nullptr);
  506. }
  507. // find first range finder instance with the specified orientation
  508. AP_RangeFinder_Backend *RangeFinder::find_instance(enum Rotation orientation) const
  509. {
  510. for (uint8_t i=0; i<num_instances; i++) {
  511. AP_RangeFinder_Backend *backend = get_backend(i);
  512. if (backend == nullptr) {
  513. continue;
  514. }
  515. if (backend->orientation() != orientation) {
  516. continue;
  517. }
  518. return backend;
  519. }
  520. return nullptr;
  521. }
  522. uint16_t RangeFinder::distance_cm_orient(enum Rotation orientation) const
  523. {
  524. AP_RangeFinder_Backend *backend = find_instance(orientation);
  525. if (backend == nullptr) {
  526. return 0;
  527. }
  528. return backend->distance_cm();
  529. }
  530. uint16_t RangeFinder::voltage_mv_orient(enum Rotation orientation) const
  531. {
  532. AP_RangeFinder_Backend *backend = find_instance(orientation);
  533. if (backend == nullptr) {
  534. return 0;
  535. }
  536. return backend->voltage_mv();
  537. }
  538. int16_t RangeFinder::max_distance_cm_orient(enum Rotation orientation) const
  539. {
  540. AP_RangeFinder_Backend *backend = find_instance(orientation);
  541. if (backend == nullptr) {
  542. return 0;
  543. }
  544. return backend->max_distance_cm();
  545. }
  546. int16_t RangeFinder::min_distance_cm_orient(enum Rotation orientation) const
  547. {
  548. AP_RangeFinder_Backend *backend = find_instance(orientation);
  549. if (backend == nullptr) {
  550. return 0;
  551. }
  552. return backend->min_distance_cm();
  553. }
  554. int16_t RangeFinder::ground_clearance_cm_orient(enum Rotation orientation) const
  555. {
  556. AP_RangeFinder_Backend *backend = find_instance(orientation);
  557. if (backend == nullptr) {
  558. return 0;
  559. }
  560. return backend->ground_clearance_cm();
  561. }
  562. bool RangeFinder::has_data_orient(enum Rotation orientation) const
  563. {
  564. AP_RangeFinder_Backend *backend = find_instance(orientation);
  565. if (backend == nullptr) {
  566. return false;
  567. }
  568. return backend->has_data();
  569. }
  570. uint8_t RangeFinder::range_valid_count_orient(enum Rotation orientation) const
  571. {
  572. AP_RangeFinder_Backend *backend = find_instance(orientation);
  573. if (backend == nullptr) {
  574. return 0;
  575. }
  576. return backend->range_valid_count();
  577. }
  578. const Vector3f &RangeFinder::get_pos_offset_orient(enum Rotation orientation) const
  579. {
  580. AP_RangeFinder_Backend *backend = find_instance(orientation);
  581. if (backend == nullptr) {
  582. return pos_offset_zero;
  583. }
  584. return backend->get_pos_offset();
  585. }
  586. uint32_t RangeFinder::last_reading_ms(enum Rotation orientation) const
  587. {
  588. AP_RangeFinder_Backend *backend = find_instance(orientation);
  589. if (backend == nullptr) {
  590. return 0;
  591. }
  592. return backend->last_reading_ms();
  593. }
  594. MAV_DISTANCE_SENSOR RangeFinder::get_mav_distance_sensor_type_orient(enum Rotation orientation) const
  595. {
  596. AP_RangeFinder_Backend *backend = find_instance(orientation);
  597. if (backend == nullptr) {
  598. return MAV_DISTANCE_SENSOR_UNKNOWN;
  599. }
  600. return backend->get_mav_distance_sensor_type();
  601. }
  602. // Write an RFND (rangefinder) packet
  603. void RangeFinder::Log_RFND()
  604. {
  605. if (_log_rfnd_bit == uint32_t(-1)) {
  606. return;
  607. }
  608. AP_Logger &logger = AP::logger();
  609. if (!logger.should_log(_log_rfnd_bit)) {
  610. return;
  611. }
  612. for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {
  613. const AP_RangeFinder_Backend *s = get_backend(i);
  614. if (s == nullptr) {
  615. continue;
  616. }
  617. const struct log_RFND pkt = {
  618. LOG_PACKET_HEADER_INIT(LOG_RFND_MSG),
  619. time_us : AP_HAL::micros64(),
  620. instance : i,
  621. dist : s->distance_cm(),
  622. status : (uint8_t)s->status(),
  623. orient : s->orientation(),
  624. };
  625. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  626. }
  627. }
  628. bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_len) const
  629. {
  630. for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
  631. if ((params[i].type != RangeFinder_TYPE_NONE) && (drivers[i] == nullptr)) {
  632. hal.util->snprintf(failure_msg, failure_msg_len, "Rangefinder %d was not detected", i + 1);
  633. return false;
  634. }
  635. }
  636. return true;
  637. }
  638. RangeFinder *RangeFinder::_singleton;
  639. namespace AP {
  640. RangeFinder *rangefinder()
  641. {
  642. return RangeFinder::get_singleton();
  643. }
  644. }