RangeFinder.h 6.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187
  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 <GCS_MAVLink/GCS.h>
  18. #include "AP_RangeFinder_Params.h"
  19. // Maximum number of range finder instances available on this platform
  20. #define RANGEFINDER_MAX_INSTANCES 10
  21. #define RANGEFINDER_GROUND_CLEARANCE_CM_DEFAULT 10
  22. #define RANGEFINDER_PREARM_ALT_MAX_CM 200
  23. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  24. #define RANGEFINDER_PREARM_REQUIRED_CHANGE_CM 0
  25. #else
  26. #define RANGEFINDER_PREARM_REQUIRED_CHANGE_CM 50
  27. #endif
  28. class AP_RangeFinder_Backend;
  29. class RangeFinder
  30. {
  31. friend class AP_RangeFinder_Backend;
  32. //UAVCAN drivers are initialised in the Backend, hence list of drivers is needed there.
  33. friend class AP_RangeFinder_UAVCAN;
  34. public:
  35. RangeFinder();
  36. /* Do not allow copies */
  37. RangeFinder(const RangeFinder &other) = delete;
  38. RangeFinder &operator=(const RangeFinder&) = delete;
  39. // RangeFinder driver types
  40. enum RangeFinder_Type {
  41. RangeFinder_TYPE_NONE = 0,
  42. RangeFinder_TYPE_ANALOG = 1,
  43. RangeFinder_TYPE_MBI2C = 2,
  44. RangeFinder_TYPE_PLI2C = 3,
  45. RangeFinder_TYPE_PX4 = 4,
  46. RangeFinder_TYPE_PX4_PWM= 5,
  47. RangeFinder_TYPE_BBB_PRU= 6,
  48. RangeFinder_TYPE_LWI2C = 7,
  49. RangeFinder_TYPE_LWSER = 8,
  50. RangeFinder_TYPE_BEBOP = 9,
  51. RangeFinder_TYPE_MAVLink = 10,
  52. RangeFinder_TYPE_ULANDING= 11,
  53. RangeFinder_TYPE_LEDDARONE = 12,
  54. RangeFinder_TYPE_MBSER = 13,
  55. RangeFinder_TYPE_TRI2C = 14,
  56. RangeFinder_TYPE_PLI2CV3= 15,
  57. RangeFinder_TYPE_VL53L0X = 16,
  58. RangeFinder_TYPE_NMEA = 17,
  59. RangeFinder_TYPE_WASP = 18,
  60. RangeFinder_TYPE_BenewakeTF02 = 19,
  61. RangeFinder_TYPE_BenewakeTFmini = 20,
  62. RangeFinder_TYPE_PLI2CV3HP = 21,
  63. RangeFinder_TYPE_PWM = 22,
  64. RangeFinder_TYPE_BLPing = 23,
  65. RangeFinder_TYPE_UAVCAN = 24,
  66. RangeFinder_TYPE_BenewakeTFminiPlus = 25,
  67. RangeFinder_TYPE_Lanbao = 26,
  68. };
  69. enum RangeFinder_Function {
  70. FUNCTION_LINEAR = 0,
  71. FUNCTION_INVERTED = 1,
  72. FUNCTION_HYPERBOLA = 2
  73. };
  74. enum RangeFinder_Status {
  75. RangeFinder_NotConnected = 0,
  76. RangeFinder_NoData,
  77. RangeFinder_OutOfRangeLow,
  78. RangeFinder_OutOfRangeHigh,
  79. RangeFinder_Good
  80. };
  81. // The RangeFinder_State structure is filled in by the backend driver
  82. struct RangeFinder_State {
  83. uint16_t distance_cm; // distance: in cm
  84. uint16_t voltage_mv; // voltage in millivolts, if applicable, otherwise 0
  85. enum RangeFinder_Status status; // sensor status
  86. uint8_t range_valid_count; // number of consecutive valid readings (maxes out at 10)
  87. uint32_t last_reading_ms; // system time of last successful update from sensor
  88. const struct AP_Param::GroupInfo *var_info;
  89. };
  90. static const struct AP_Param::GroupInfo *backend_var_info[RANGEFINDER_MAX_INSTANCES];
  91. // parameters for each instance
  92. static const struct AP_Param::GroupInfo var_info[];
  93. void set_log_rfnd_bit(uint32_t log_rfnd_bit) { _log_rfnd_bit = log_rfnd_bit; }
  94. // Return the number of range finder instances
  95. uint8_t num_sensors(void) const {
  96. return num_instances;
  97. }
  98. // prearm checks
  99. bool prearm_healthy(char *failure_msg, const uint8_t failure_msg_len) const;
  100. // detect and initialise any available rangefinders
  101. void init(enum Rotation orientation_default);
  102. // update state of all rangefinders. Should be called at around
  103. // 10Hz from main loop
  104. void update(void);
  105. // Handle an incoming DISTANCE_SENSOR message (from a MAVLink enabled range finder)
  106. void handle_msg(const mavlink_message_t &msg);
  107. // return true if we have a range finder with the specified orientation
  108. bool has_orientation(enum Rotation orientation) const;
  109. // find first range finder instance with the specified orientation
  110. AP_RangeFinder_Backend *find_instance(enum Rotation orientation) const;
  111. AP_RangeFinder_Backend *get_backend(uint8_t id) const;
  112. // methods to return a distance on a particular orientation from
  113. // any sensor which can current supply it
  114. uint16_t distance_cm_orient(enum Rotation orientation) const;
  115. uint16_t voltage_mv_orient(enum Rotation orientation) const;
  116. int16_t max_distance_cm_orient(enum Rotation orientation) const;
  117. int16_t min_distance_cm_orient(enum Rotation orientation) const;
  118. int16_t ground_clearance_cm_orient(enum Rotation orientation) const;
  119. MAV_DISTANCE_SENSOR get_mav_distance_sensor_type_orient(enum Rotation orientation) const;
  120. RangeFinder_Status status_orient(enum Rotation orientation) const;
  121. bool has_data_orient(enum Rotation orientation) const;
  122. uint8_t range_valid_count_orient(enum Rotation orientation) const;
  123. const Vector3f &get_pos_offset_orient(enum Rotation orientation) const;
  124. uint32_t last_reading_ms(enum Rotation orientation) const;
  125. // indicate which bit in LOG_BITMASK indicates RFND should be logged
  126. void set_rfnd_bit(uint32_t log_rfnd_bit) { _log_rfnd_bit = log_rfnd_bit; }
  127. /*
  128. set an externally estimated terrain height. Used to enable power
  129. saving (where available) at high altitudes.
  130. */
  131. void set_estimated_terrain_height(float height) {
  132. estimated_terrain_height = height;
  133. }
  134. static RangeFinder *get_singleton(void) { return _singleton; }
  135. protected:
  136. AP_RangeFinder_Params params[RANGEFINDER_MAX_INSTANCES];
  137. private:
  138. static RangeFinder *_singleton;
  139. RangeFinder_State state[RANGEFINDER_MAX_INSTANCES];
  140. AP_RangeFinder_Backend *drivers[RANGEFINDER_MAX_INSTANCES];
  141. uint8_t num_instances;
  142. float estimated_terrain_height;
  143. Vector3f pos_offset_zero; // allows returning position offsets of zero for invalid requests
  144. void convert_params(void);
  145. void detect_instance(uint8_t instance, uint8_t& serial_instance);
  146. bool _add_backend(AP_RangeFinder_Backend *driver);
  147. uint32_t _log_rfnd_bit = -1;
  148. void Log_RFND();
  149. };
  150. namespace AP {
  151. RangeFinder *rangefinder();
  152. };