rplidar_driver.cpp
Go to the documentation of this file.
1 /*
2  * Slamtec LIDAR SDK
3  *
4  * Copyright (c) 2014 - 2020 Shanghai Slamtec Co., Ltd.
5  * http://www.slamtec.com
6  *
7  */
8  /*
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions are met:
11  *
12  * 1. Redistributions of source code must retain the above copyright notice,
13  * this list of conditions and the following disclaimer.
14  *
15  * 2. Redistributions in binary form must reproduce the above copyright notice,
16  * this list of conditions and the following disclaimer in the documentation
17  * and/or other materials provided with the distribution.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
21  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
22  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
24  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
25  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
26  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
27  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
28  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
29  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30  *
31  */
32 
33 #include "sdkcommon.h"
34 #include "hal/abs_rxtx.h"
35 #include "hal/thread.h"
36 #include "hal/types.h"
37 #include "hal/assert.h"
38 #include "hal/locker.h"
39 #include "hal/socket.h"
40 #include "hal/event.h"
41 #include "rplidar_driver.h"
42 #include "sl_crc.h"
43 #include <algorithm>
44 
45 namespace rp { namespace standalone{ namespace rplidar {
46 
48 
49  RPlidarDriver::RPlidarDriver(sl_u32 channelType)
50  :_channelType(channelType)
51  {
52  }
53 
55 
57  {
58  //_channelType = drivertype;
59  return new RPlidarDriver(drivertype);
60  }
61 
63  {
64  delete drv;
65  }
66 
67  u_result RPlidarDriver::connect(const char *path, _u32 portOrBaud, _u32 flag)
68  {
69  switch (_channelType)
70  {
72  _channel = (*createSerialPortChannel(path, portOrBaud));
73  break;
74  case CHANNEL_TYPE_TCP:
75  _channel = *createTcpChannel(path, portOrBaud);
76  break;
77  case CHANNEL_TYPE_UDP:
78  _channel = *createUdpChannel(path, portOrBaud);
79  break;
80  }
81  if (!(bool)_channel) return SL_RESULT_OPERATION_FAIL;
82 
84 
85  if (!(bool)_lidarDrv) return SL_RESULT_OPERATION_FAIL;
86 
87  sl_result ans =(_lidarDrv)->connect(_channel);
88  return ans;
89  }
90 
92  {
93  (_lidarDrv)->disconnect();
94  }
95 
97  {
98  return (_lidarDrv)->isConnected();
99  }
100 
102  {
103  return (_lidarDrv)->reset();
104  }
105 
106  u_result RPlidarDriver::getAllSupportedScanModes(std::vector<RplidarScanMode>& outModes, _u32 timeoutInMs)
107  {
108  return (_lidarDrv)->getAllSupportedScanModes(outModes, timeoutInMs);
109  }
110 
112  {
113  return (_lidarDrv)->getTypicalScanMode(outMode, timeoutInMs);
114  }
115 
116  u_result RPlidarDriver::startScan(bool force, bool useTypicalScan, _u32 options, RplidarScanMode* outUsedScanMode)
117  {
118  return (_lidarDrv)->startScan(force, useTypicalScan, options, outUsedScanMode);
119  }
120 
121  u_result RPlidarDriver::startScanExpress(bool force, _u16 scanMode, _u32 options, RplidarScanMode* outUsedScanMode, _u32 timeout)
122  {
123  return (_lidarDrv)->startScanExpress(force, scanMode, options, outUsedScanMode, timeout);
124  }
125 
127  {
128  return (_lidarDrv)->getHealth(health, timeout);
129  }
130 
132  {
133  return (_lidarDrv)->getDeviceInfo(info, timeout);
134  }
135 
137  {
138  return (_lidarDrv)->setMotorSpeed(pwm);
139  }
140 
142  {
143  MotorCtrlSupport motorSupport;
144  u_result ans = (_lidarDrv)->checkMotorCtrlSupport(motorSupport, timeout);
145  if (motorSupport == MotorCtrlSupportNone)
146  support = false;
147  return ans;
148  }
149 
151  {
152  return (_lidarDrv)->setLidarIpConf(conf, timeout);
153  }
154 
155  u_result RPlidarDriver::getDeviceMacAddr(_u8* macAddrArray, _u32 timeoutInMs)
156  {
157  return (_lidarDrv)->getDeviceMacAddr(macAddrArray, timeoutInMs);
158  }
159 
161  {
162  return (_lidarDrv)->stop(timeout);
163  }
164 
166  {
167  return (_lidarDrv)->grabScanDataHq(nodebuffer, count, timeout);
168  }
169 
171  {
172  return (_lidarDrv)->ascendScanData(nodebuffer, count);
173  }
174 
176  {
178  }
179 
181  {
182  return (_lidarDrv)->getScanDataWithIntervalHq(nodebuffer, count);
183  }
184 
186  {
187  return (_lidarDrv)->setMotorSpeed(600);
188  }
190  {
191  return (_lidarDrv)->setMotorSpeed(0);
192  }
193 
194 }}}
sl_lidar_response_device_health_t rplidar_response_device_health_t
Definition: rplidar_cmd.h:194
u_result setLidarIpConf(const rplidar_ip_conf_t &conf, _u32 timeout=DEFAULT_TIMEOUT)
Result< IChannel * > createUdpChannel(const std::string &ip, int port)
u_result getScanDataWithInterval(rplidar_response_measurement_node_t *nodebuffer, size_t &count)
u_result getScanDataWithIntervalHq(rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count)
u_result getDeviceInfo(rplidar_response_device_info_t &info, _u32 timeout=DEFAULT_TIMEOUT)
static void DisposeDriver(RPlidarDriver *drv)
u_result startScanExpress(bool force, _u16 scanMode, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL, _u32 timeout=DEFAULT_TIMEOUT)
u_result reset(_u32 timeout=DEFAULT_TIMEOUT)
sl_lidar_ip_conf_t rplidar_ip_conf_t
Definition: rplidar_cmd.h:195
u_result stop(_u32 timeout=DEFAULT_TIMEOUT)
u_result getAllSupportedScanModes(std::vector< RplidarScanMode > &outModes, _u32 timeoutInMs=DEFAULT_TIMEOUT)
Get all scan modes that supported by lidar.
MotorCtrlSupport
u_result getTypicalScanMode(_u16 &outMode, _u32 timeoutInMs=DEFAULT_TIMEOUT)
Get typical scan mode of lidar.
uint8_t _u8
Definition: rptypes.h:63
u_result ascendScanData(rplidar_response_measurement_node_hq_t *nodebuffer, size_t count)
u_result startScan(bool force, bool useTypicalScan, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL)
sl_u8 flag
Definition: sl_lidar_cmd.h:43
Result< ILidarDriver * > createLidarDriver()
static RPlidarDriver * CreateDriver(_u32 drivertype=CHANNEL_TYPE_SERIALPORT)
bool isConnected()
Returns TRUE when the connection has been established.
sl_lidar_response_measurement_node_t rplidar_response_measurement_node_t
Definition: rplidar_cmd.h:134
u_result getHealth(rplidar_response_device_health_t &health, _u32 timeout=DEFAULT_TIMEOUT)
u_result connect(const char *path, _u32 portOrBaud, _u32 flag=0)
u_result getDeviceMacAddr(_u8 *macAddrArray, _u32 timeoutInMs=DEFAULT_TIMEOUT)
ILidarDriver * drv
Definition: node.cpp:54
u_result startMotor()
Start RPLIDAR&#39;s motor when using accessory board.
u_result checkMotorCtrlSupport(bool &support, _u32 timeout=DEFAULT_TIMEOUT)
uint32_t _u32
Definition: rptypes.h:69
u_result grabScanDataHq(rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)
#define RESULT_OPERATION_NOT_SUPPORT
Definition: rptypes.h:109
#define SL_RESULT_OPERATION_FAIL
Definition: sl_types.h:75
sl_lidar_response_device_info_t rplidar_response_device_info_t
Definition: rplidar_cmd.h:193
Result< IChannel * > createSerialPortChannel(const std::string &device, int baudrate)
void disconnect()
Disconnect with the RPLIDAR and close the serial port.
uint16_t _u16
Definition: rptypes.h:66
uint32_t sl_result
Definition: sl_types.h:69
u_result stopMotor()
Stop RPLIDAR&#39;s motor when using accessory board.
Result< IChannel * > createTcpChannel(const std::string &ip, int port)
uint32_t u_result
Definition: rptypes.h:100


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