AP_Proximity_MAV.cpp 6.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172
  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. #include "AP_Proximity_MAV.h"
  15. #include <AP_SerialManager/AP_SerialManager.h>
  16. #include <ctype.h>
  17. #include <stdio.h>
  18. extern const AP_HAL::HAL& hal;
  19. #define PROXIMITY_MAV_TIMEOUT_MS 500 // distance messages must arrive within this many milliseconds
  20. /*
  21. The constructor also initialises the proximity sensor. Note that this
  22. constructor is not called until detect() returns true, so we
  23. already know that we should setup the proximity sensor
  24. */
  25. AP_Proximity_MAV::AP_Proximity_MAV(AP_Proximity &_frontend,
  26. AP_Proximity::Proximity_State &_state) :
  27. AP_Proximity_Backend(_frontend, _state)
  28. {
  29. }
  30. // update the state of the sensor
  31. void AP_Proximity_MAV::update(void)
  32. {
  33. // check for timeout and set health status
  34. if ((_last_update_ms == 0 || (AP_HAL::millis() - _last_update_ms > PROXIMITY_MAV_TIMEOUT_MS)) &&
  35. (_last_upward_update_ms == 0 || (AP_HAL::millis() - _last_upward_update_ms > PROXIMITY_MAV_TIMEOUT_MS))) {
  36. set_status(AP_Proximity::Proximity_NoData);
  37. } else {
  38. set_status(AP_Proximity::Proximity_Good);
  39. }
  40. }
  41. // get distance upwards in meters. returns true on success
  42. bool AP_Proximity_MAV::get_upward_distance(float &distance) const
  43. {
  44. if ((_last_upward_update_ms != 0) && (AP_HAL::millis() - _last_upward_update_ms <= PROXIMITY_MAV_TIMEOUT_MS)) {
  45. distance = _distance_upward;
  46. return true;
  47. }
  48. return false;
  49. }
  50. // handle mavlink DISTANCE_SENSOR messages
  51. void AP_Proximity_MAV::handle_msg(const mavlink_message_t &msg)
  52. {
  53. if (msg.msgid == MAVLINK_MSG_ID_DISTANCE_SENSOR) {
  54. mavlink_distance_sensor_t packet;
  55. mavlink_msg_distance_sensor_decode(&msg, &packet);
  56. // store distance to appropriate sector based on orientation field
  57. if (packet.orientation <= MAV_SENSOR_ROTATION_YAW_315) {
  58. uint8_t sector = packet.orientation;
  59. _angle[sector] = sector * 45;
  60. _distance[sector] = packet.current_distance * 0.01f;
  61. _distance_min = packet.min_distance * 0.01f;
  62. _distance_max = packet.max_distance * 0.01f;
  63. _distance_valid[sector] = (_distance[sector] >= _distance_min) && (_distance[sector] <= _distance_max);
  64. _last_update_ms = AP_HAL::millis();
  65. update_boundary_for_sector(sector, true);
  66. }
  67. // store upward distance
  68. if (packet.orientation == MAV_SENSOR_ROTATION_PITCH_90) {
  69. _distance_upward = packet.current_distance * 0.01f;
  70. _last_upward_update_ms = AP_HAL::millis();
  71. }
  72. return;
  73. }
  74. if (msg.msgid == MAVLINK_MSG_ID_OBSTACLE_DISTANCE) {
  75. mavlink_obstacle_distance_t packet;
  76. mavlink_msg_obstacle_distance_decode(&msg, &packet);
  77. // check increment (message's sector width)
  78. float increment;
  79. if (!is_zero(packet.increment_f)) {
  80. // use increment float
  81. increment = packet.increment_f;
  82. } else if (packet.increment != 0) {
  83. // use increment uint8_t
  84. increment = packet.increment;
  85. } else {
  86. // invalid increment
  87. return;
  88. }
  89. const float MAX_DISTANCE = 9999.0f;
  90. const uint8_t total_distances = MIN(((360.0f / fabsf(increment)) + 0.5f), MAVLINK_MSG_OBSTACLE_DISTANCE_FIELD_DISTANCES_LEN); // usually 72
  91. // set distance min and max
  92. _distance_min = packet.min_distance * 0.01f;
  93. _distance_max = packet.max_distance * 0.01f;
  94. _last_update_ms = AP_HAL::millis();
  95. // get user configured yaw correction from front end
  96. const float param_yaw_offset = constrain_float(frontend.get_yaw_correction(state.instance), -360.0f, +360.0f);
  97. const float yaw_correction = wrap_360(param_yaw_offset + packet.angle_offset);
  98. if (frontend.get_orientation(state.instance) != 0) {
  99. increment *= -1;
  100. }
  101. Location current_loc;
  102. float current_vehicle_bearing;
  103. const bool database_ready = database_prepare_for_push(current_loc, current_vehicle_bearing);
  104. // initialise updated array and proximity sector angles (to closest object) and distances
  105. bool sector_updated[_num_sectors];
  106. float sector_width_half[_num_sectors];
  107. for (uint8_t i = 0; i < _num_sectors; i++) {
  108. sector_updated[i] = false;
  109. sector_width_half[i] = _sector_width_deg[i] * 0.5f;
  110. _angle[i] = _sector_middle_deg[i];
  111. _distance[i] = MAX_DISTANCE;
  112. }
  113. // iterate over message's sectors
  114. for (uint8_t j = 0; j < total_distances; j++) {
  115. const uint16_t distance_cm = packet.distances[j];
  116. if (distance_cm == 0 ||
  117. distance_cm == 65535 ||
  118. distance_cm < packet.min_distance ||
  119. distance_cm > packet.max_distance)
  120. {
  121. // sanity check failed, ignore this distance value
  122. continue;
  123. }
  124. const float packet_distance_m = distance_cm * 0.01f;
  125. const float mid_angle = wrap_360((float)j * increment + yaw_correction);
  126. // iterate over proximity sectors
  127. for (uint8_t i = 0; i < _num_sectors; i++) {
  128. float angle_diff = fabsf(wrap_180(_sector_middle_deg[i] - mid_angle));
  129. // update distance array sector with shortest distance from message
  130. if ((angle_diff <= sector_width_half[i]) && (packet_distance_m < _distance[i])) {
  131. _distance[i] = packet_distance_m;
  132. _angle[i] = mid_angle;
  133. sector_updated[i] = true;
  134. }
  135. }
  136. // update Object Avoidance database with Earth-frame point
  137. if (database_ready) {
  138. database_push(mid_angle, packet_distance_m, _last_update_ms, current_loc, current_vehicle_bearing);
  139. }
  140. }
  141. // update proximity sectors validity and boundary point
  142. for (uint8_t i = 0; i < _num_sectors; i++) {
  143. _distance_valid[i] = (_distance[i] >= _distance_min) && (_distance[i] <= _distance_max);
  144. if (sector_updated[i]) {
  145. update_boundary_for_sector(i, false);
  146. }
  147. }
  148. }
  149. }