AP_Proximity.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483
  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 "AP_Proximity.h"
  14. #include "AP_Proximity_LightWareSF40C.h"
  15. #include "AP_Proximity_RPLidarA2.h"
  16. #include "AP_Proximity_TeraRangerTower.h"
  17. #include "AP_Proximity_TeraRangerTowerEvo.h"
  18. #include "AP_Proximity_RangeFinder.h"
  19. #include "AP_Proximity_MAV.h"
  20. #include "AP_Proximity_SITL.h"
  21. #include "AP_Proximity_MorseSITL.h"
  22. #include "AP_Proximity_AirSimSITL.h"
  23. #include <AP_AHRS/AP_AHRS.h>
  24. extern const AP_HAL::HAL &hal;
  25. // table of user settable parameters
  26. const AP_Param::GroupInfo AP_Proximity::var_info[] = {
  27. // 0 is reserved for possible addition of an ENABLED parameter
  28. // @Param: _TYPE
  29. // @DisplayName: Proximity type
  30. // @Description: What type of proximity sensor is connected
  31. // @Values: 0:None,1:LightWareSF40C,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2,6:TeraRangerTowerEvo,10:SITL,11:MorseSITL,12:AirSimSITL
  32. // @RebootRequired: True
  33. // @User: Standard
  34. AP_GROUPINFO("_TYPE", 1, AP_Proximity, _type[0], 0),
  35. // @Param: _ORIENT
  36. // @DisplayName: Proximity sensor orientation
  37. // @Description: Proximity sensor orientation
  38. // @Values: 0:Default,1:Upside Down
  39. // @User: Standard
  40. AP_GROUPINFO("_ORIENT", 2, AP_Proximity, _orientation[0], 0),
  41. // @Param: _YAW_CORR
  42. // @DisplayName: Proximity sensor yaw correction
  43. // @Description: Proximity sensor yaw correction
  44. // @Units: deg
  45. // @Range: -180 180
  46. // @User: Standard
  47. AP_GROUPINFO("_YAW_CORR", 3, AP_Proximity, _yaw_correction[0], 0),
  48. // @Param: _IGN_ANG1
  49. // @DisplayName: Proximity sensor ignore angle 1
  50. // @Description: Proximity sensor ignore angle 1
  51. // @Units: deg
  52. // @Range: 0 360
  53. // @User: Standard
  54. AP_GROUPINFO("_IGN_ANG1", 4, AP_Proximity, _ignore_angle_deg[0], 0),
  55. // @Param: _IGN_WID1
  56. // @DisplayName: Proximity sensor ignore width 1
  57. // @Description: Proximity sensor ignore width 1
  58. // @Units: deg
  59. // @Range: 0 45
  60. // @User: Standard
  61. AP_GROUPINFO("_IGN_WID1", 5, AP_Proximity, _ignore_width_deg[0], 0),
  62. // @Param: _IGN_ANG2
  63. // @DisplayName: Proximity sensor ignore angle 2
  64. // @Description: Proximity sensor ignore angle 2
  65. // @Units: deg
  66. // @Range: 0 360
  67. // @User: Standard
  68. AP_GROUPINFO("_IGN_ANG2", 6, AP_Proximity, _ignore_angle_deg[1], 0),
  69. // @Param: _IGN_WID2
  70. // @DisplayName: Proximity sensor ignore width 2
  71. // @Description: Proximity sensor ignore width 2
  72. // @Units: deg
  73. // @Range: 0 45
  74. // @User: Standard
  75. AP_GROUPINFO("_IGN_WID2", 7, AP_Proximity, _ignore_width_deg[1], 0),
  76. // @Param: _IGN_ANG3
  77. // @DisplayName: Proximity sensor ignore angle 3
  78. // @Description: Proximity sensor ignore angle 3
  79. // @Units: deg
  80. // @Range: 0 360
  81. // @User: Standard
  82. AP_GROUPINFO("_IGN_ANG3", 8, AP_Proximity, _ignore_angle_deg[2], 0),
  83. // @Param: _IGN_WID3
  84. // @DisplayName: Proximity sensor ignore width 3
  85. // @Description: Proximity sensor ignore width 3
  86. // @Units: deg
  87. // @Range: 0 45
  88. // @User: Standard
  89. AP_GROUPINFO("_IGN_WID3", 9, AP_Proximity, _ignore_width_deg[2], 0),
  90. // @Param: _IGN_ANG4
  91. // @DisplayName: Proximity sensor ignore angle 4
  92. // @Description: Proximity sensor ignore angle 4
  93. // @Units: deg
  94. // @Range: 0 360
  95. // @User: Standard
  96. AP_GROUPINFO("_IGN_ANG4", 10, AP_Proximity, _ignore_angle_deg[3], 0),
  97. // @Param: _IGN_WID4
  98. // @DisplayName: Proximity sensor ignore width 4
  99. // @Description: Proximity sensor ignore width 4
  100. // @Units: deg
  101. // @Range: 0 45
  102. // @User: Standard
  103. AP_GROUPINFO("_IGN_WID4", 11, AP_Proximity, _ignore_width_deg[3], 0),
  104. // @Param: _IGN_ANG5
  105. // @DisplayName: Proximity sensor ignore angle 5
  106. // @Description: Proximity sensor ignore angle 5
  107. // @Units: deg
  108. // @Range: 0 360
  109. // @User: Standard
  110. AP_GROUPINFO("_IGN_ANG5", 12, AP_Proximity, _ignore_angle_deg[4], 0),
  111. // @Param: _IGN_WID5
  112. // @DisplayName: Proximity sensor ignore width 5
  113. // @Description: Proximity sensor ignore width 5
  114. // @Units: deg
  115. // @Range: 0 45
  116. // @User: Standard
  117. AP_GROUPINFO("_IGN_WID5", 13, AP_Proximity, _ignore_width_deg[4], 0),
  118. // @Param: _IGN_ANG6
  119. // @DisplayName: Proximity sensor ignore angle 6
  120. // @Description: Proximity sensor ignore angle 6
  121. // @Units: deg
  122. // @Range: 0 360
  123. // @User: Standard
  124. AP_GROUPINFO("_IGN_ANG6", 14, AP_Proximity, _ignore_angle_deg[5], 0),
  125. // @Param: _IGN_WID6
  126. // @DisplayName: Proximity sensor ignore width 6
  127. // @Description: Proximity sensor ignore width 6
  128. // @Units: deg
  129. // @Range: 0 45
  130. // @User: Standard
  131. AP_GROUPINFO("_IGN_WID6", 15, AP_Proximity, _ignore_width_deg[5], 0),
  132. #if PROXIMITY_MAX_INSTANCES > 1
  133. // @Param: 2_TYPE
  134. // @DisplayName: Second Proximity type
  135. // @Description: What type of proximity sensor is connected
  136. // @Values: 0:None,1:LightWareSF40C,2:MAVLink,3:TeraRangerTower,4:RangeFinder,5:RPLidarA2,6:TeraRangerTowerEvo
  137. // @User: Advanced
  138. // @RebootRequired: True
  139. AP_GROUPINFO("2_TYPE", 16, AP_Proximity, _type[1], 0),
  140. // @Param: 2_ORIENT
  141. // @DisplayName: Second Proximity sensor orientation
  142. // @Description: Second Proximity sensor orientation
  143. // @Values: 0:Default,1:Upside Down
  144. // @User: Standard
  145. AP_GROUPINFO("2_ORIENT", 17, AP_Proximity, _orientation[1], 0),
  146. // @Param: 2_YAW_CORR
  147. // @DisplayName: Second Proximity sensor yaw correction
  148. // @Description: Second Proximity sensor yaw correction
  149. // @Units: deg
  150. // @Range: -180 180
  151. // @User: Standard
  152. AP_GROUPINFO("2_YAW_CORR", 18, AP_Proximity, _yaw_correction[1], 0),
  153. #endif
  154. AP_GROUPEND
  155. };
  156. AP_Proximity::AP_Proximity(AP_SerialManager &_serial_manager) :
  157. serial_manager(_serial_manager)
  158. {
  159. AP_Param::setup_object_defaults(this, var_info);
  160. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  161. if (_singleton != nullptr) {
  162. AP_HAL::panic("AP_Proximity must be singleton");
  163. }
  164. #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
  165. _singleton = this;
  166. }
  167. // initialise the Proximity class. We do detection of attached sensors here
  168. // we don't allow for hot-plugging of sensors (i.e. reboot required)
  169. void AP_Proximity::init(void)
  170. {
  171. if (num_instances != 0) {
  172. // init called a 2nd time?
  173. return;
  174. }
  175. for (uint8_t i=0; i<PROXIMITY_MAX_INSTANCES; i++) {
  176. detect_instance(i);
  177. if (drivers[i] != nullptr) {
  178. // we loaded a driver for this instance, so it must be
  179. // present (although it may not be healthy)
  180. num_instances = i+1;
  181. }
  182. // initialise status
  183. state[i].status = Proximity_NotConnected;
  184. }
  185. }
  186. // update Proximity state for all instances. This should be called at a high rate by the main loop
  187. void AP_Proximity::update(void)
  188. {
  189. for (uint8_t i=0; i<num_instances; i++) {
  190. if (drivers[i] != nullptr) {
  191. if (_type[i] == Proximity_Type_None) {
  192. // allow user to disable a proximity sensor at runtime
  193. state[i].status = Proximity_NotConnected;
  194. continue;
  195. }
  196. drivers[i]->update();
  197. }
  198. }
  199. // work out primary instance - first sensor returning good data
  200. for (int8_t i=num_instances-1; i>=0; i--) {
  201. if (drivers[i] != nullptr && (state[i].status == Proximity_Good)) {
  202. primary_instance = i;
  203. }
  204. }
  205. }
  206. // return sensor orientation
  207. uint8_t AP_Proximity::get_orientation(uint8_t instance) const
  208. {
  209. if (instance >= PROXIMITY_MAX_INSTANCES) {
  210. return 0;
  211. }
  212. return _orientation[instance].get();
  213. }
  214. // return sensor yaw correction
  215. int16_t AP_Proximity::get_yaw_correction(uint8_t instance) const
  216. {
  217. if (instance >= PROXIMITY_MAX_INSTANCES) {
  218. return 0;
  219. }
  220. return _yaw_correction[instance].get();
  221. }
  222. // return sensor health
  223. AP_Proximity::Proximity_Status AP_Proximity::get_status(uint8_t instance) const
  224. {
  225. // sanity check instance number
  226. if (instance >= num_instances) {
  227. return Proximity_NotConnected;
  228. }
  229. return state[instance].status;
  230. }
  231. AP_Proximity::Proximity_Status AP_Proximity::get_status() const
  232. {
  233. return get_status(primary_instance);
  234. }
  235. // handle mavlink DISTANCE_SENSOR messages
  236. void AP_Proximity::handle_msg(const mavlink_message_t &msg)
  237. {
  238. for (uint8_t i=0; i<num_instances; i++) {
  239. if ((drivers[i] != nullptr) && (_type[i] != Proximity_Type_None)) {
  240. drivers[i]->handle_msg(msg);
  241. }
  242. }
  243. }
  244. // detect if an instance of a proximity sensor is connected.
  245. void AP_Proximity::detect_instance(uint8_t instance)
  246. {
  247. uint8_t type = _type[instance];
  248. if (type == Proximity_Type_SF40C) {
  249. if (AP_Proximity_LightWareSF40C::detect(serial_manager)) {
  250. state[instance].instance = instance;
  251. drivers[instance] = new AP_Proximity_LightWareSF40C(*this, state[instance], serial_manager);
  252. return;
  253. }
  254. }
  255. if (type == Proximity_Type_RPLidarA2) {
  256. if (AP_Proximity_RPLidarA2::detect(serial_manager)) {
  257. state[instance].instance = instance;
  258. drivers[instance] = new AP_Proximity_RPLidarA2(*this, state[instance], serial_manager);
  259. return;
  260. }
  261. }
  262. if (type == Proximity_Type_MAV) {
  263. state[instance].instance = instance;
  264. drivers[instance] = new AP_Proximity_MAV(*this, state[instance]);
  265. return;
  266. }
  267. if (type == Proximity_Type_TRTOWER) {
  268. if (AP_Proximity_TeraRangerTower::detect(serial_manager)) {
  269. state[instance].instance = instance;
  270. drivers[instance] = new AP_Proximity_TeraRangerTower(*this, state[instance], serial_manager);
  271. return;
  272. }
  273. }
  274. if (type == Proximity_Type_TRTOWEREVO) {
  275. if (AP_Proximity_TeraRangerTowerEvo::detect(serial_manager)) {
  276. state[instance].instance = instance;
  277. drivers[instance] = new AP_Proximity_TeraRangerTowerEvo(*this, state[instance], serial_manager);
  278. return;
  279. }
  280. }
  281. if (type == Proximity_Type_RangeFinder) {
  282. state[instance].instance = instance;
  283. drivers[instance] = new AP_Proximity_RangeFinder(*this, state[instance]);
  284. return;
  285. }
  286. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  287. if (type == Proximity_Type_SITL) {
  288. state[instance].instance = instance;
  289. drivers[instance] = new AP_Proximity_SITL(*this, state[instance]);
  290. return;
  291. }
  292. if (type == Proximity_Type_MorseSITL) {
  293. state[instance].instance = instance;
  294. drivers[instance] = new AP_Proximity_MorseSITL(*this, state[instance]);
  295. return;
  296. }
  297. if (type == Proximity_Type_AirSimSITL) {
  298. state[instance].instance = instance;
  299. drivers[instance] = new AP_Proximity_AirSimSITL(*this, state[instance]);
  300. return;
  301. }
  302. #endif
  303. }
  304. // get distance in meters in a particular direction in degrees (0 is forward, clockwise)
  305. // returns true on successful read and places distance in distance
  306. bool AP_Proximity::get_horizontal_distance(uint8_t instance, float angle_deg, float &distance) const
  307. {
  308. if ((drivers[instance] == nullptr) || (_type[instance] == Proximity_Type_None)) {
  309. return false;
  310. }
  311. // get distance from backend
  312. return drivers[instance]->get_horizontal_distance(angle_deg, distance);
  313. }
  314. // get distance in meters in a particular direction in degrees (0 is forward, clockwise)
  315. // returns true on successful read and places distance in distance
  316. bool AP_Proximity::get_horizontal_distance(float angle_deg, float &distance) const
  317. {
  318. return get_horizontal_distance(primary_instance, angle_deg, distance);
  319. }
  320. // get distances in 8 directions. used for sending distances to ground station
  321. bool AP_Proximity::get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const
  322. {
  323. if ((drivers[primary_instance] == nullptr) || (_type[primary_instance] == Proximity_Type_None)) {
  324. return false;
  325. }
  326. // get distances from backend
  327. return drivers[primary_instance]->get_horizontal_distances(prx_dist_array);
  328. }
  329. // get boundary points around vehicle for use by avoidance
  330. // returns nullptr and sets num_points to zero if no boundary can be returned
  331. const Vector2f* AP_Proximity::get_boundary_points(uint8_t instance, uint16_t& num_points) const
  332. {
  333. if ((drivers[instance] == nullptr) || (_type[instance] == Proximity_Type_None)) {
  334. num_points = 0;
  335. return nullptr;
  336. }
  337. // get boundary from backend
  338. return drivers[instance]->get_boundary_points(num_points);
  339. }
  340. const Vector2f* AP_Proximity::get_boundary_points(uint16_t& num_points) const
  341. {
  342. return get_boundary_points(primary_instance, num_points);
  343. }
  344. // get distance and angle to closest object (used for pre-arm check)
  345. // returns true on success, false if no valid readings
  346. bool AP_Proximity::get_closest_object(float& angle_deg, float &distance) const
  347. {
  348. if ((drivers[primary_instance] == nullptr) || (_type[primary_instance] == Proximity_Type_None)) {
  349. return false;
  350. }
  351. // get closest object from backend
  352. return drivers[primary_instance]->get_closest_object(angle_deg, distance);
  353. }
  354. // get number of objects, used for non-GPS avoidance
  355. uint8_t AP_Proximity::get_object_count() const
  356. {
  357. if ((drivers[primary_instance] == nullptr) || (_type[primary_instance] == Proximity_Type_None)) {
  358. return 0;
  359. }
  360. // get count from backend
  361. return drivers[primary_instance]->get_object_count();
  362. }
  363. // get an object's angle and distance, used for non-GPS avoidance
  364. // returns false if no angle or distance could be returned for some reason
  365. bool AP_Proximity::get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const
  366. {
  367. if ((drivers[primary_instance] == nullptr) || (_type[primary_instance] == Proximity_Type_None)) {
  368. return false;
  369. }
  370. // get angle and distance from backend
  371. return drivers[primary_instance]->get_object_angle_and_distance(object_number, angle_deg, distance);
  372. }
  373. // get maximum and minimum distances (in meters) of primary sensor
  374. float AP_Proximity::distance_max() const
  375. {
  376. if ((drivers[primary_instance] == nullptr) || (_type[primary_instance] == Proximity_Type_None)) {
  377. return 0.0f;
  378. }
  379. // get maximum distance from backend
  380. return drivers[primary_instance]->distance_max();
  381. }
  382. float AP_Proximity::distance_min() const
  383. {
  384. if ((drivers[primary_instance] == nullptr) || (_type[primary_instance] == Proximity_Type_None)) {
  385. return 0.0f;
  386. }
  387. // get minimum distance from backend
  388. return drivers[primary_instance]->distance_min();
  389. }
  390. // get distance in meters upwards, returns true on success
  391. bool AP_Proximity::get_upward_distance(uint8_t instance, float &distance) const
  392. {
  393. if ((drivers[instance] == nullptr) || (_type[instance] == Proximity_Type_None)) {
  394. return false;
  395. }
  396. // get upward distance from backend
  397. return drivers[instance]->get_upward_distance(distance);
  398. }
  399. bool AP_Proximity::get_upward_distance(float &distance) const
  400. {
  401. return get_upward_distance(primary_instance, distance);
  402. }
  403. AP_Proximity::Proximity_Type AP_Proximity::get_type(uint8_t instance) const
  404. {
  405. if (instance < PROXIMITY_MAX_INSTANCES) {
  406. return (Proximity_Type)((uint8_t)_type[instance]);
  407. }
  408. return Proximity_Type_None;
  409. }
  410. bool AP_Proximity::sensor_present() const
  411. {
  412. return get_status() != Proximity_NotConnected;
  413. }
  414. bool AP_Proximity::sensor_enabled() const
  415. {
  416. return _type[primary_instance] != Proximity_Type_None;
  417. }
  418. bool AP_Proximity::sensor_failed() const
  419. {
  420. return get_status() != Proximity_Good;
  421. }
  422. AP_Proximity *AP_Proximity::_singleton;
  423. namespace AP {
  424. AP_Proximity *proximity()
  425. {
  426. return AP_Proximity::get_singleton();
  427. }
  428. }