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 {
51 };
52 
54 public:
55  enum {
56  DEFAULT_TIMEOUT = 2000, //2000 ms
57  };
58 
59  enum {
60  MAX_SCAN_NODES = 8192,
61  };
62 
63  enum {
64  LEGACY_SAMPLE_DURATION = 476,
65  };
66 
67 public:
72  static RPlidarDriver * CreateDriver(_u32 drivertype = CHANNEL_TYPE_SERIALPORT);
73 
74 
75  RPlidarDriver(sl_u32 channelType);
76 
79  static void DisposeDriver(RPlidarDriver * drv);
80 
92  u_result connect(const char *path, _u32 portOrBaud, _u32 flag = 0);
93 
95  void disconnect();
96 
98  bool isConnected();
99 
104  u_result reset(_u32 timeout = DEFAULT_TIMEOUT);
105 
107  return RESULT_OK;
108  }
109  // FW1.24
111  u_result getAllSupportedScanModes(std::vector<RplidarScanMode>& outModes, _u32 timeoutInMs = DEFAULT_TIMEOUT);
112 
114  u_result getTypicalScanMode(_u16& outMode, _u32 timeoutInMs = DEFAULT_TIMEOUT);
115 
122  u_result startScan(bool force, bool useTypicalScan, _u32 options = 0, RplidarScanMode* outUsedScanMode = NULL);
123 
130  u_result startScanExpress(bool force, _u16 scanMode, _u32 options = 0, RplidarScanMode* outUsedScanMode = NULL, _u32 timeout = DEFAULT_TIMEOUT);
131 
138  u_result getHealth(rplidar_response_device_health_t & health, _u32 timeout = DEFAULT_TIMEOUT);
139 
144  u_result getDeviceInfo(rplidar_response_device_info_t & info, _u32 timeout = DEFAULT_TIMEOUT);
145 
149  u_result setMotorPWM(_u16 pwm);
150 
152  u_result startMotor();
153 
155  u_result stopMotor();
156 
162  u_result checkMotorCtrlSupport(bool & support, _u32 timeout = DEFAULT_TIMEOUT);
163 
168  u_result setLidarIpConf(const rplidar_ip_conf_t& conf, _u32 timeout = DEFAULT_TIMEOUT);
169 
174  u_result getLidarIpConf(rplidar_ip_conf_t& conf, _u32 timeout = DEFAULT_TIMEOUT);
175 
179  u_result getDeviceMacAddr(_u8* macAddrArray, _u32 timeoutInMs = DEFAULT_TIMEOUT);
180 
184  u_result stop(_u32 timeout = DEFAULT_TIMEOUT);
185 
203  u_result grabScanDataHq(rplidar_response_measurement_node_hq_t * nodebuffer, size_t & count, _u32 timeout = DEFAULT_TIMEOUT);
204 
212  u_result ascendScanData(rplidar_response_measurement_node_hq_t * nodebuffer, size_t count);
213 
221  u_result getScanDataWithInterval(rplidar_response_measurement_node_t * nodebuffer, size_t & count);
222 
230  u_result getScanDataWithIntervalHq(rplidar_response_measurement_node_hq_t * nodebuffer, size_t & count);
231 
232 
233  virtual ~RPlidarDriver();
234 protected:
235  RPlidarDriver();
236 
237 private:
238  sl_u32 _channelType;
241 
242 };
243 
244 
245 
246 
247 }}}
_u16
uint16_t _u16
Definition: rptypes.h:66
rp::standalone::rplidar::DRIVER_TYPE_SERIALPORT
@ DRIVER_TYPE_SERIALPORT
Definition: rplidar_driver.h:48
u_result
uint32_t u_result
Definition: rptypes.h:100
sl_lidar_response_measurement_node_hq_t
Definition: sl_lidar_cmd.h:272
rp::standalone::rplidar::RPlidarDriver::clearNetSerialRxCache
u_result clearNetSerialRxCache()
Definition: rplidar_driver.h:106
sl::IChannel
Definition: sl_lidar_driver.h:171
rp::standalone::rplidar::RPlidarDriver::_channelType
sl_u32 _channelType
Definition: rplidar_driver.h:238
RESULT_OK
#define RESULT_OK
Definition: rptypes.h:102
rp::standalone::rplidar::RPlidarDriver::_channel
IChannel * _channel
Definition: rplidar_driver.h:239
sl::ILidarDriver
Definition: sl_lidar_driver.h:306
_u8
uint8_t _u8
Definition: rptypes.h:63
rp::standalone::rplidar::DRIVER_TYPE_UDP
@ DRIVER_TYPE_UDP
Definition: rplidar_driver.h:50
sl::LidarScanMode
Definition: sl_lidar_driver.h:73
rplidar_response_measurement_node_t
sl_lidar_response_measurement_node_t rplidar_response_measurement_node_t
Definition: rplidar_cmd.h:136
rp::standalone::rplidar::RPlidarDriver::_lidarDrv
ILidarDriver * _lidarDrv
Definition: rplidar_driver.h:240
rplidar_ip_conf_t
sl_lidar_ip_conf_t rplidar_ip_conf_t
Definition: rplidar_cmd.h:197
rp::standalone::rplidar::RplidarScanMode
LidarScanMode RplidarScanMode
Definition: rplidar_driver.h:45
sl
Definition: sl_crc.h:38
sl::CHANNEL_TYPE_SERIALPORT
@ CHANNEL_TYPE_SERIALPORT
Definition: sl_lidar_driver.h:284
rplidar_response_device_info_t
sl_lidar_response_device_info_t rplidar_response_device_info_t
Definition: rplidar_cmd.h:195
rp::standalone::rplidar::DRIVER_TYPE_TCP
@ DRIVER_TYPE_TCP
Definition: rplidar_driver.h:49
flag
sl_u8 flag
Definition: sl_lidar_cmd.h:2
drv
ILidarDriver * drv
Definition: node.cpp:54
rp
Definition: rplidar_driver.h:43
_u32
uint32_t _u32
Definition: rptypes.h:69
rplidar_response_device_health_t
sl_lidar_response_device_health_t rplidar_response_device_health_t
Definition: rplidar_cmd.h:196
rp::standalone::rplidar::RPlidarDriver
Definition: rplidar_driver.h:53
sl_lidar_driver.h


rplidar_ros
Author(s):
autogenerated on Fri Aug 2 2024 08:42:14