AP_Proximity_RPLidarA2.h 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128
  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. /*
  14. * ArduPilot device driver for SLAMTEC RPLIDAR A2 (16m range version)
  15. *
  16. * ALL INFORMATION REGARDING PROTOCOL WAS DERIVED FROM RPLIDAR DATASHEET:
  17. *
  18. * https://www.slamtec.com/en/Lidar
  19. * http://bucket.download.slamtec.com/63ac3f0d8c859d3a10e51c6b3285fcce25a47357/LR001_SLAMTEC_rplidar_protocol_v1.0_en.pdf
  20. *
  21. * Author: Steven Josefs, IAV GmbH
  22. * Based on the LightWare SF40C ArduPilot device driver from Randy Mackay
  23. *
  24. */
  25. #pragma once
  26. #include "AP_Proximity.h"
  27. #include "AP_Proximity_Backend.h"
  28. #include <AP_HAL/AP_HAL.h> ///< for UARTDriver
  29. class AP_Proximity_RPLidarA2 : public AP_Proximity_Backend
  30. {
  31. public:
  32. // constructor
  33. AP_Proximity_RPLidarA2(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state, AP_SerialManager &serial_manager);
  34. // static detection function
  35. static bool detect(AP_SerialManager &serial_manager);
  36. // update state
  37. void update(void) override;
  38. // get maximum and minimum distances (in meters) of sensor
  39. float distance_max() const override;
  40. float distance_min() const override;
  41. private:
  42. enum rp_state {
  43. rp_unknown = 0,
  44. rp_resetted,
  45. rp_responding,
  46. rp_measurements,
  47. rp_health
  48. };
  49. enum ResponseType {
  50. ResponseType_Descriptor = 0,
  51. ResponseType_SCAN,
  52. ResponseType_EXPRESS,
  53. ResponseType_Health
  54. };
  55. // initialise sensor (returns true if sensor is successfully initialised)
  56. bool initialise();
  57. void init_sectors();
  58. void set_scan_mode();
  59. // send request for something from sensor
  60. void send_request_for_health();
  61. void parse_response_data();
  62. void parse_response_descriptor();
  63. void get_readings();
  64. void reset_rplidar();
  65. // reply related variables
  66. AP_HAL::UARTDriver *_uart;
  67. uint8_t _descriptor[7];
  68. char _rp_systeminfo[63];
  69. bool _descriptor_data;
  70. bool _information_data;
  71. bool _resetted;
  72. bool _initialised;
  73. bool _sector_initialised;
  74. uint8_t _payload_length;
  75. uint8_t _cnt;
  76. uint8_t _sync_error ;
  77. uint16_t _byte_count;
  78. // request related variables
  79. enum ResponseType _response_type; ///< response from the lidar
  80. enum rp_state _rp_state;
  81. uint8_t _last_sector; ///< last sector requested
  82. uint32_t _last_request_ms; ///< system time of last request
  83. uint32_t _last_distance_received_ms; ///< system time of last distance measurement received from sensor
  84. uint32_t _last_reset_ms;
  85. // sector related variables
  86. float _angle_deg_last;
  87. float _distance_m_last;
  88. struct PACKED _sensor_scan {
  89. uint8_t startbit : 1; ///< on the first revolution 1 else 0
  90. uint8_t not_startbit : 1; ///< complementary to startbit
  91. uint8_t quality : 6; ///< Related the reflected laser pulse strength
  92. uint8_t checkbit : 1; ///< always set to 1
  93. uint16_t angle_q6 : 15; ///< Actual heading = angle_q6/64.0 Degree
  94. uint16_t distance_q2 : 16; ///< Actual Distance = distance_q2/4.0 mm
  95. };
  96. struct PACKED _sensor_health {
  97. uint8_t status; ///< status definition: 0 good, 1 warning, 2 error
  98. uint16_t error_code; ///< the related error code
  99. };
  100. union PACKED {
  101. DEFINE_BYTE_ARRAY_METHODS
  102. _sensor_scan sensor_scan;
  103. _sensor_health sensor_health;
  104. } payload;
  105. };