AP_Proximity_SITL.cpp 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140
  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_Param/AP_Param.h>
  16. #include "AP_Proximity_SITL.h"
  17. #include <stdio.h>
  18. extern const AP_HAL::HAL& hal;
  19. #define PROXIMITY_MAX_RANGE 200.0f
  20. #define PROXIMITY_ACCURACY 0.1f
  21. /*
  22. The constructor also initialises the proximity sensor.
  23. */
  24. AP_Proximity_SITL::AP_Proximity_SITL(AP_Proximity &_frontend,
  25. AP_Proximity::Proximity_State &_state):
  26. AP_Proximity_Backend(_frontend, _state),
  27. sitl(AP::sitl())
  28. {
  29. ap_var_type ptype;
  30. fence_count = (AP_Int8 *)AP_Param::find("FENCE_TOTAL", &ptype);
  31. if (fence_count == nullptr || ptype != AP_PARAM_INT8) {
  32. AP_HAL::panic("Proximity_SITL: Failed to find FENCE_TOTAL");
  33. }
  34. fence_alt_max = (AP_Float *)AP_Param::find("FENCE_ALT_MAX", &ptype);
  35. if (fence_alt_max == nullptr || ptype != AP_PARAM_FLOAT) {
  36. AP_HAL::panic("Proximity_SITL: Failed to find FENCE_ALT_MAX");
  37. }
  38. }
  39. // update the state of the sensor
  40. void AP_Proximity_SITL::update(void)
  41. {
  42. load_fence();
  43. current_loc.lat = sitl->state.latitude * 1.0e7;
  44. current_loc.lng = sitl->state.longitude * 1.0e7;
  45. current_loc.alt = sitl->state.altitude * 1.0e2;
  46. if (fence && fence_loader.boundary_valid(fence_count->get(), fence)) {
  47. // update distance in one sector
  48. if (get_distance_to_fence(_sector_middle_deg[last_sector], _distance[last_sector])) {
  49. set_status(AP_Proximity::Proximity_Good);
  50. _distance_valid[last_sector] = true;
  51. _angle[last_sector] = _sector_middle_deg[last_sector];
  52. update_boundary_for_sector(last_sector, true);
  53. } else {
  54. _distance_valid[last_sector] = false;
  55. }
  56. last_sector++;
  57. if (last_sector >= _num_sectors) {
  58. last_sector = 0;
  59. }
  60. } else {
  61. set_status(AP_Proximity::Proximity_NoData);
  62. }
  63. }
  64. void AP_Proximity_SITL::load_fence(void)
  65. {
  66. uint32_t now = AP_HAL::millis();
  67. if (now - last_load_ms < 1000) {
  68. return;
  69. }
  70. last_load_ms = now;
  71. if (fence == nullptr) {
  72. fence = (Vector2l *)fence_loader.create_point_array(sizeof(Vector2l));
  73. }
  74. if (fence == nullptr) {
  75. return;
  76. }
  77. for (uint8_t i=0; i<fence_count->get(); i++) {
  78. fence_loader.load_point_from_eeprom(i, fence[i]);
  79. }
  80. }
  81. // get distance in meters to fence in a particular direction in degrees (0 is forward, angles increase in the clockwise direction)
  82. bool AP_Proximity_SITL::get_distance_to_fence(float angle_deg, float &distance) const
  83. {
  84. if (!fence_loader.boundary_valid(fence_count->get(), fence)) {
  85. return false;
  86. }
  87. // convert to earth frame
  88. angle_deg = wrap_360(sitl->state.yawDeg + angle_deg);
  89. /*
  90. simple bisection search to find distance. Not really efficient,
  91. but we can afford the CPU in SITL
  92. */
  93. float min_dist = 0, max_dist = PROXIMITY_MAX_RANGE;
  94. while (max_dist - min_dist > PROXIMITY_ACCURACY) {
  95. float test_dist = (max_dist+min_dist)*0.5f;
  96. Location loc = current_loc;
  97. loc.offset_bearing(angle_deg, test_dist);
  98. Vector2l vecloc(loc.lat, loc.lng);
  99. if (fence_loader.boundary_breached(vecloc, fence_count->get(), fence)) {
  100. max_dist = test_dist;
  101. } else {
  102. min_dist = test_dist;
  103. }
  104. }
  105. distance = min_dist;
  106. return true;
  107. }
  108. // get maximum and minimum distances (in meters) of primary sensor
  109. float AP_Proximity_SITL::distance_max() const
  110. {
  111. return PROXIMITY_MAX_RANGE;
  112. }
  113. float AP_Proximity_SITL::distance_min() const
  114. {
  115. return 0.0f;
  116. }
  117. // get distance upwards in meters. returns true on success
  118. bool AP_Proximity_SITL::get_upward_distance(float &distance) const
  119. {
  120. // return distance to fence altitude
  121. distance = MAX(0.0f, fence_alt_max->get() - sitl->height_agl);
  122. return true;
  123. }
  124. #endif // CONFIG_HAL_BOARD