AP_Proximity_MorseSITL.cpp 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104
  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_HAL/AP_HAL.h>
  14. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  15. #include "AP_Proximity_MorseSITL.h"
  16. #include <stdio.h>
  17. extern const AP_HAL::HAL& hal;
  18. #define PROXIMITY_MAX_RANGE 200.0f
  19. #define PROXIMITY_ACCURACY 0.1f
  20. /*
  21. The constructor also initialises the proximity sensor.
  22. */
  23. AP_Proximity_MorseSITL::AP_Proximity_MorseSITL(AP_Proximity &_frontend,
  24. AP_Proximity::Proximity_State &_state):
  25. AP_Proximity_Backend(_frontend, _state),
  26. sitl(AP::sitl())
  27. {
  28. }
  29. // update the state of the sensor
  30. void AP_Proximity_MorseSITL::update(void)
  31. {
  32. SITL::vector3f_array &points = sitl->state.scanner.points;
  33. SITL::float_array &ranges = sitl->state.scanner.ranges;
  34. if (points.length != ranges.length ||
  35. points.length == 0) {
  36. set_status(AP_Proximity::Proximity_NoData);
  37. return;
  38. }
  39. set_status(AP_Proximity::Proximity_Good);
  40. memset(_distance_valid, 0, sizeof(_distance_valid));
  41. memset(_angle, 0, sizeof(_angle));
  42. memset(_distance, 0, sizeof(_distance));
  43. // only use 8 sectors to match RPLidar
  44. const uint8_t nsectors = MIN(8, PROXIMITY_SECTORS_MAX);
  45. const uint16_t degrees_per_sector = 360 / nsectors;
  46. for (uint16_t i=0; i<points.length; i++) {
  47. Vector3f &point = points.data[i];
  48. float &range = ranges.data[i];
  49. distance_maximum = MAX(distance_maximum, range);
  50. if (point.is_zero()) {
  51. continue;
  52. }
  53. float angle_deg = wrap_360(degrees(atan2f(-point.y, point.x)));
  54. uint16_t angle_rounded = uint16_t(angle_deg+0.5);
  55. uint8_t sector = wrap_360(angle_rounded + 22.5f) / degrees_per_sector;
  56. if (!_distance_valid[sector] || range < _distance[sector]) {
  57. _distance_valid[sector] = true;
  58. _distance[sector] = range;
  59. _angle[sector] = angle_deg;
  60. update_boundary_for_sector(sector, true);
  61. }
  62. }
  63. #if 0
  64. printf("npoints=%u\n", points.length);
  65. for (uint16_t i=0; i<nsectors; i++) {
  66. printf("sector[%u] ang=%.1f dist=%.1f\n", i, _angle[i], _distance[i]);
  67. }
  68. #endif
  69. }
  70. // get maximum and minimum distances (in meters) of primary sensor
  71. float AP_Proximity_MorseSITL::distance_max() const
  72. {
  73. // we don't have a data field from Morse for max range, so we use the max
  74. // we've ever seen
  75. return distance_maximum;
  76. }
  77. float AP_Proximity_MorseSITL::distance_min() const
  78. {
  79. return 0.0f;
  80. }
  81. // get distance upwards in meters. returns true on success
  82. bool AP_Proximity_MorseSITL::get_upward_distance(float &distance) const
  83. {
  84. // we don't have an upward facing laser
  85. return false;
  86. }
  87. #endif // CONFIG_HAL_BOARD