rplidar_driver.h
Go to the documentation of this file.
1 /*
2  * RPLIDAR SDK
3  *
4  * Copyright (c) 2009 - 2014 RoboPeak Team
5  * http://www.robopeak.com
6  * Copyright (c) 2014 - 2019 Shanghai Slamtec Co., Ltd.
7  * http://www.slamtec.com
8  *
9  */
10 /*
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions are met:
13  *
14  * 1. Redistributions of source code must retain the above copyright notice,
15  * this list of conditions and the following disclaimer.
16  *
17  * 2. Redistributions in binary form must reproduce the above copyright notice,
18  * this list of conditions and the following disclaimer in the documentation
19  * and/or other materials provided with the distribution.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
23  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
24  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
25  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
26  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
27  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
28  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
29  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
30  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
31  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *
33  */
34 
35 #pragma once
36 #include "sl_lidar_driver.h"
37 
38 #ifndef __cplusplus
39 #error "The RPlidar SDK requires a C++ compiler to be built"
40 #endif
41 
42 
43 namespace rp { namespace standalone{ namespace rplidar {
44  using namespace sl;
46 
47 //enum {
48 // DRIVER_TYPE_SERIALPORT = 0x0,
49 // DRIVER_TYPE_TCP = 0x1,
50 // DRIVER_TYPE_UDP = 0x2,
51 //};
53 public:
54  enum {
55  DEFAULT_TIMEOUT = 2000, //2000 ms
56  };
57 
58  enum {
60  };
61 
62  enum {
63  LEGACY_SAMPLE_DURATION = 476,
64  };
65 
66 public:
71  static RPlidarDriver * CreateDriver(_u32 drivertype = CHANNEL_TYPE_SERIALPORT);
72 
73 
74  RPlidarDriver(sl_u32 channelType);
75 
78  static void DisposeDriver(RPlidarDriver * drv);
79 
91  u_result connect(const char *path, _u32 portOrBaud, _u32 flag = 0);
92 
94  void disconnect();
95 
97  bool isConnected();
98 
103  u_result reset(_u32 timeout = DEFAULT_TIMEOUT);
104 
106  return RESULT_OK;
107  }
108  // FW1.24
110  u_result getAllSupportedScanModes(std::vector<RplidarScanMode>& outModes, _u32 timeoutInMs = DEFAULT_TIMEOUT);
111 
113  u_result getTypicalScanMode(_u16& outMode, _u32 timeoutInMs = DEFAULT_TIMEOUT);
114 
121  u_result startScan(bool force, bool useTypicalScan, _u32 options = 0, RplidarScanMode* outUsedScanMode = NULL);
122 
129  u_result startScanExpress(bool force, _u16 scanMode, _u32 options = 0, RplidarScanMode* outUsedScanMode = NULL, _u32 timeout = DEFAULT_TIMEOUT);
130 
137  u_result getHealth(rplidar_response_device_health_t & health, _u32 timeout = DEFAULT_TIMEOUT);
138 
143  u_result getDeviceInfo(rplidar_response_device_info_t & info, _u32 timeout = DEFAULT_TIMEOUT);
144 
148  u_result setMotorPWM(_u16 pwm);
149 
151  u_result startMotor();
152 
154  u_result stopMotor();
155 
161  u_result checkMotorCtrlSupport(bool & support, _u32 timeout = DEFAULT_TIMEOUT);
162 
167  u_result setLidarIpConf(const rplidar_ip_conf_t& conf, _u32 timeout = DEFAULT_TIMEOUT);
168 
172  u_result getDeviceMacAddr(_u8* macAddrArray, _u32 timeoutInMs = DEFAULT_TIMEOUT);
173 
177  u_result stop(_u32 timeout = DEFAULT_TIMEOUT);
178 
196  u_result grabScanDataHq(rplidar_response_measurement_node_hq_t * nodebuffer, size_t & count, _u32 timeout = DEFAULT_TIMEOUT);
197 
205  u_result ascendScanData(rplidar_response_measurement_node_hq_t * nodebuffer, size_t count);
206 
214  u_result getScanDataWithInterval(rplidar_response_measurement_node_t * nodebuffer, size_t & count);
215 
223  u_result getScanDataWithIntervalHq(rplidar_response_measurement_node_hq_t * nodebuffer, size_t & count);
224 
225 
226  virtual ~RPlidarDriver();
227 protected:
228  RPlidarDriver();
229 
230 private:
231  sl_u32 _channelType;
234 
235 };
236 
237 
238 
239 
240 }}}
sl_lidar_response_device_health_t rplidar_response_device_health_t
Definition: rplidar_cmd.h:194
Definition: sl_crc.h:38
#define MAX_SCAN_NODES
#define RESULT_OK
Definition: rptypes.h:102
sl_lidar_ip_conf_t rplidar_ip_conf_t
Definition: rplidar_cmd.h:195
uint8_t _u8
Definition: rptypes.h:63
sl_u8 flag
Definition: sl_lidar_cmd.h:43
sl_lidar_response_measurement_node_t rplidar_response_measurement_node_t
Definition: rplidar_cmd.h:134
ILidarDriver * drv
Definition: node.cpp:54
uint32_t _u32
Definition: rptypes.h:69
LidarScanMode RplidarScanMode
sl_lidar_response_device_info_t rplidar_response_device_info_t
Definition: rplidar_cmd.h:193
uint16_t _u16
Definition: rptypes.h:66
uint32_t u_result
Definition: rptypes.h:100


rplidar_ros
Author(s):
autogenerated on Tue Jun 13 2023 02:07:38