AP_Proximity_Backend.h 5.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111
  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. #pragma once
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_HAL/AP_HAL.h>
  16. #include "AP_Proximity.h"
  17. #include <AP_Common/Location.h>
  18. #define PROXIMITY_SECTORS_MAX 12 // maximum number of sectors
  19. #define PROXIMITY_BOUNDARY_DIST_MIN 0.6f // minimum distance for a boundary point. This ensures the object avoidance code doesn't think we are outside the boundary.
  20. #define PROXIMITY_BOUNDARY_DIST_DEFAULT 100 // if we have no data for a sector, boundary is placed 100m out
  21. class AP_Proximity_Backend
  22. {
  23. public:
  24. // constructor. This incorporates initialisation as well.
  25. AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state);
  26. // we declare a virtual destructor so that Proximity drivers can
  27. // override with a custom destructor if need be
  28. virtual ~AP_Proximity_Backend(void) {}
  29. // update the state structure
  30. virtual void update() = 0;
  31. // get maximum and minimum distances (in meters) of sensor
  32. virtual float distance_max() const = 0;
  33. virtual float distance_min() const = 0;
  34. // get distance upwards in meters. returns true on success
  35. virtual bool get_upward_distance(float &distance) const { return false; }
  36. // handle mavlink DISTANCE_SENSOR messages
  37. virtual void handle_msg(const mavlink_message_t &msg) {}
  38. // get distance in meters in a particular direction in degrees (0 is forward, clockwise)
  39. // returns true on successful read and places distance in distance
  40. bool get_horizontal_distance(float angle_deg, float &distance) const;
  41. // get boundary points around vehicle for use by avoidance
  42. // returns nullptr and sets num_points to zero if no boundary can be returned
  43. const Vector2f* get_boundary_points(uint16_t& num_points) const;
  44. // get distance and angle to closest object (used for pre-arm check)
  45. // returns true on success, false if no valid readings
  46. bool get_closest_object(float& angle_deg, float &distance) const;
  47. // get number of objects, angle and distance - used for non-GPS avoidance
  48. uint8_t get_object_count() const;
  49. bool get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const;
  50. // get distances in 8 directions. used for sending distances to ground station
  51. bool get_horizontal_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const;
  52. protected:
  53. // set status and update valid_count
  54. void set_status(AP_Proximity::Proximity_Status status);
  55. // find which sector a given angle falls into
  56. bool convert_angle_to_sector(float angle_degrees, uint8_t &sector) const;
  57. // initialise the boundary and sector_edge_vector array used for object avoidance
  58. // should be called if the sector_middle_deg or _setor_width_deg arrays are changed
  59. void init_boundary();
  60. // update boundary points used for object avoidance based on a single sector's distance changing
  61. // the boundary points lie on the line between sectors meaning two boundary points may be updated based on a single sector's distance changing
  62. // the boundary point is set to the shortest distance found in the two adjacent sectors, this is a conservative boundary around the vehicle
  63. void update_boundary_for_sector(const uint8_t sector, const bool push_to_OA_DB);
  64. // get ignore area info
  65. uint8_t get_ignore_area_count() const;
  66. bool get_ignore_area(uint8_t index, uint16_t &angle_deg, uint8_t &width_deg) const;
  67. bool get_next_ignore_start_or_end(uint8_t start_or_end, int16_t start_angle, int16_t &ignore_start) const;
  68. // database helpers
  69. bool database_prepare_for_push(Location &current_loc, float &current_vehicle_bearing);
  70. void database_push(const float angle, const float distance);
  71. void database_push(const float angle, const float distance, const uint32_t timestamp_ms, const Location &current_loc, const float current_vehicle_bearing);
  72. AP_Proximity &frontend;
  73. AP_Proximity::Proximity_State &state; // reference to this instances state
  74. // sectors
  75. uint8_t _num_sectors = PROXIMITY_MAX_DIRECTION;
  76. uint16_t _sector_middle_deg[PROXIMITY_SECTORS_MAX] = {0, 45, 90, 135, 180, 225, 270, 315, 0, 0, 0, 0}; // middle angle of each sector
  77. uint8_t _sector_width_deg[PROXIMITY_SECTORS_MAX] = {45, 45, 45, 45, 45, 45, 45, 45, 0, 0, 0, 0}; // width (in degrees) of each sector
  78. // sensor data
  79. float _angle[PROXIMITY_SECTORS_MAX]; // angle to closest object within each sector
  80. float _distance[PROXIMITY_SECTORS_MAX]; // distance to closest object within each sector
  81. bool _distance_valid[PROXIMITY_SECTORS_MAX]; // true if a valid distance received for each sector
  82. // fence boundary
  83. Vector2f _sector_edge_vector[PROXIMITY_SECTORS_MAX]; // vector for right-edge of each sector, used to speed up calculation of boundary
  84. Vector2f _boundary_point[PROXIMITY_SECTORS_MAX]; // bounding polygon around the vehicle calculated conservatively for object avoidance
  85. };