APM:Libraries
AP_Proximity_RPLidarA2.h
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * ArduPilot device driver for SLAMTEC RPLIDAR A2 (16m range version)
18  *
19  * ALL INFORMATION REGARDING PROTOCOL WAS DERIVED FROM RPLIDAR DATASHEET:
20  *
21  * https://www.slamtec.com/en/Lidar
22  * http://bucket.download.slamtec.com/63ac3f0d8c859d3a10e51c6b3285fcce25a47357/LR001_SLAMTEC_rplidar_protocol_v1.0_en.pdf
23  *
24  * Author: Steven Josefs, IAV GmbH
25  * Based on the LightWare SF40C ArduPilot device driver from Randy Mackay
26  *
27  */
28 
29 
30 #pragma once
31 
32 #include "AP_Proximity.h"
33 #include "AP_Proximity_Backend.h"
34 #include <AP_HAL/AP_HAL.h>
35 
36 
38 {
39 
40 public:
41  // constructor
43 
44  // static detection function
45  static bool detect(AP_SerialManager &serial_manager);
46 
47  // update state
48  void update(void);
49 
50  // get maximum and minimum distances (in meters) of sensor
51  float distance_max() const;
52  float distance_min() const;
53 
54 private:
55  enum rp_state {
61  };
62 
63  enum ResponseType {
68  };
69 
70  // initialise sensor (returns true if sensor is successfully initialised)
71  bool initialise();
72  void init_sectors();
73  void set_scan_mode();
74 
75  // send request for something from sensor
77  void parse_response_data();
79  void get_readings();
80  void reset_rplidar();
81 
82  // reply related variables
84  uint8_t _descriptor[7];
85  char _rp_systeminfo[63];
88  bool _resetted;
91 
92  uint8_t _payload_length;
93  uint8_t _cnt;
94  uint8_t _sync_error ;
95  uint16_t _byte_count;
96 
97  // request related variables
100  uint8_t _last_sector;
101  uint32_t _last_request_ms;
103  uint32_t _last_reset_ms;
104 
105  // sector related variables
108 
110  uint8_t startbit : 1;
111  uint8_t not_startbit : 1;
112  uint8_t quality : 6;
113  uint8_t checkbit : 1;
114  uint16_t angle_q6 : 15;
115  uint16_t distance_q2 : 16;
116  };
117 
119  uint8_t status;
120  uint16_t error_code;
121  };
122 
123  union PACKED {
127  } payload;
128 };
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
uint32_t _last_distance_received_ms
system time of last distance measurement received from sensor
union AP_Proximity_RPLidarA2::PACKED payload
AP_HAL::UARTDriver * _uart
#define DEFINE_BYTE_ARRAY_METHODS
Definition: AP_Common.h:58
uint8_t status
status definition: 0 good, 1 warning, 2 error
uint8_t quality
Related the reflected laser pulse strength.
uint16_t angle_q6
Actual heading = angle_q6/64.0 Degree.
uint8_t startbit
on the first revolution 1 else 0
AP_Proximity_RPLidarA2(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state, AP_SerialManager &serial_manager)
uint32_t _last_request_ms
system time of last request
static bool detect(AP_SerialManager &serial_manager)
uint8_t _last_sector
last sector requested
uint8_t not_startbit
complementary to startbit
uint16_t distance_q2
Actual Distance = distance_q2/4.0 mm.
DEFINE_BYTE_ARRAY_METHODS _sensor_scan sensor_scan
enum ResponseType _response_type
response from the lidar
uint16_t error_code
the related error code