AP_Proximity.h 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166
  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_Param/AP_Param.h>
  17. #include <AP_Math/AP_Math.h>
  18. #include <AP_SerialManager/AP_SerialManager.h>
  19. #include <AP_RangeFinder/AP_RangeFinder.h>
  20. #define PROXIMITY_MAX_INSTANCES 1 // Maximum number of proximity sensor instances available on this platform
  21. #define PROXIMITY_MAX_IGNORE 6 // up to six areas can be ignored
  22. #define PROXIMITY_MAX_DIRECTION 8
  23. #define PROXIMITY_SENSOR_ID_START 10
  24. class AP_Proximity_Backend;
  25. class AP_Proximity
  26. {
  27. public:
  28. friend class AP_Proximity_Backend;
  29. AP_Proximity(AP_SerialManager &_serial_manager);
  30. AP_Proximity(const AP_Proximity &other) = delete;
  31. AP_Proximity &operator=(const AP_Proximity) = delete;
  32. // Proximity driver types
  33. enum Proximity_Type {
  34. Proximity_Type_None = 0,
  35. Proximity_Type_SF40C = 1,
  36. Proximity_Type_MAV = 2,
  37. Proximity_Type_TRTOWER = 3,
  38. Proximity_Type_RangeFinder = 4,
  39. Proximity_Type_RPLidarA2 = 5,
  40. Proximity_Type_TRTOWEREVO = 6,
  41. Proximity_Type_SITL = 10,
  42. Proximity_Type_MorseSITL = 11,
  43. Proximity_Type_AirSimSITL = 12,
  44. };
  45. enum Proximity_Status {
  46. Proximity_NotConnected = 0,
  47. Proximity_NoData,
  48. Proximity_Good
  49. };
  50. // structure holding distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station
  51. struct Proximity_Distance_Array {
  52. uint8_t orientation[PROXIMITY_MAX_DIRECTION]; // orientation (i.e. rough direction) of the distance (see MAV_SENSOR_ORIENTATION)
  53. float distance[PROXIMITY_MAX_DIRECTION]; // distance in meters
  54. };
  55. // detect and initialise any available proximity sensors
  56. void init(void);
  57. // update state of all proximity sensors. Should be called at high rate from main loop
  58. void update(void);
  59. // set pointer to rangefinder object
  60. void set_rangefinder(const RangeFinder *rangefinder) { _rangefinder = rangefinder; }
  61. const RangeFinder *get_rangefinder() const { return _rangefinder; }
  62. // return sensor orientation and yaw correction
  63. uint8_t get_orientation(uint8_t instance) const;
  64. int16_t get_yaw_correction(uint8_t instance) const;
  65. // return sensor health
  66. Proximity_Status get_status(uint8_t instance) const;
  67. Proximity_Status get_status() const;
  68. // Return the number of proximity sensors
  69. uint8_t num_sensors(void) const {
  70. return num_instances;
  71. }
  72. // get distance in meters in a particular direction in degrees (0 is forward, clockwise)
  73. // returns true on successful read and places distance in distance
  74. bool get_horizontal_distance(uint8_t instance, float angle_deg, float &distance) const;
  75. bool get_horizontal_distance(float angle_deg, float &distance) const;
  76. // get distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station
  77. bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const;
  78. // get boundary points around vehicle for use by avoidance
  79. // returns nullptr and sets num_points to zero if no boundary can be returned
  80. const Vector2f* get_boundary_points(uint8_t instance, uint16_t& num_points) const;
  81. const Vector2f* get_boundary_points(uint16_t& num_points) const;
  82. // get distance and angle to closest object (used for pre-arm check)
  83. // returns true on success, false if no valid readings
  84. bool get_closest_object(float& angle_deg, float &distance) const;
  85. // get number of objects, angle and distance - used for non-GPS avoidance
  86. uint8_t get_object_count() const;
  87. bool get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const;
  88. // get maximum and minimum distances (in meters) of primary sensor
  89. float distance_max() const;
  90. float distance_min() const;
  91. // handle mavlink DISTANCE_SENSOR messages
  92. void handle_msg(const mavlink_message_t &msg);
  93. // The Proximity_State structure is filled in by the backend driver
  94. struct Proximity_State {
  95. uint8_t instance; // the instance number of this proximity sensor
  96. enum Proximity_Status status; // sensor status
  97. };
  98. //
  99. // support for upward facing sensors
  100. //
  101. // get distance upwards in meters. returns true on success
  102. bool get_upward_distance(uint8_t instance, float &distance) const;
  103. bool get_upward_distance(float &distance) const;
  104. Proximity_Type get_type(uint8_t instance) const;
  105. // parameter list
  106. static const struct AP_Param::GroupInfo var_info[];
  107. static AP_Proximity *get_singleton(void) { return _singleton; };
  108. // methods for mavlink SYS_STATUS message (send_sys_status)
  109. // these methods cover only the primary instance
  110. bool sensor_present() const;
  111. bool sensor_enabled() const;
  112. bool sensor_failed() const;
  113. private:
  114. static AP_Proximity *_singleton;
  115. Proximity_State state[PROXIMITY_MAX_INSTANCES];
  116. AP_Proximity_Backend *drivers[PROXIMITY_MAX_INSTANCES];
  117. const RangeFinder *_rangefinder;
  118. uint8_t primary_instance;
  119. uint8_t num_instances;
  120. AP_SerialManager &serial_manager;
  121. // parameters for all instances
  122. AP_Int8 _type[PROXIMITY_MAX_INSTANCES];
  123. AP_Int8 _orientation[PROXIMITY_MAX_INSTANCES];
  124. AP_Int16 _yaw_correction[PROXIMITY_MAX_INSTANCES];
  125. AP_Int16 _ignore_angle_deg[PROXIMITY_MAX_IGNORE]; // angle (in degrees) of area that should be ignored by sensor (i.e. leg shows up)
  126. AP_Int8 _ignore_width_deg[PROXIMITY_MAX_IGNORE]; // width of beam (in degrees) that should be ignored
  127. void detect_instance(uint8_t instance);
  128. };
  129. namespace AP {
  130. AP_Proximity *proximity();
  131. };