sl_lidar_driver.h
Go to the documentation of this file.
1 /*
2  * Slamtec LIDAR SDK
3  *
4  * Copyright (c) 2020 Shanghai Slamtec Co., Ltd.
5  * http://www.slamtec.com
6  */
7  /*
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions are met:
10  *
11  * 1. Redistributions of source code must retain the above copyright notice,
12  * this list of conditions and the following disclaimer.
13  *
14  * 2. Redistributions in binary form must reproduce the above copyright notice,
15  * this list of conditions and the following disclaimer in the documentation
16  * and/or other materials provided with the distribution.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
20  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
21  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
22  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
23  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
24  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
25  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
26  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
27  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
28  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29  *
30  */
31 
32 #pragma once
33 
34 #ifndef __cplusplus
35 #error "The Slamtec LIDAR SDK requires a C++ compiler to be built"
36 #endif
37 
38 #include <vector>
39 #include <map>
40 #include <string>
41 
42 #ifndef DEPRECATED
43  #ifdef __GNUC__
44  #define DEPRECATED(func) func __attribute__ ((deprecated))
45  #elif defined(_MSC_VER)
46  #define DEPRECATED(func) __declspec(deprecated) func
47  #else
48  #pragma message("WARNING: You need to implement DEPRECATED for this compiler")
49  #define DEPRECATED(func) func
50  #endif
51 #endif
52 
53 
54 #include "sl_lidar_cmd.h"
55 
56 #include <string>
57 
58 namespace sl {
59 
60 #ifdef DEPRECATED
61 #define DEPRECATED_WARN(fn, replacement) do { \
62  static bool __shown__ = false; \
63  if (!__shown__) { \
64  printDeprecationWarn(fn, replacement); \
65  __shown__ = true; \
66  } \
67  } while (0)
68 #endif
69 
74  {
75  // Mode id
76  sl_u16 id;
77 
78  // Time cost for one measurement (in microseconds)
80 
81  // Max distance in this scan mode (in meters)
82  float max_distance;
83 
84  // The answer command code for this scan mode
85  sl_u8 ans_type;
86 
87  // The name of scan mode (padding with 0 if less than 64 characters)
88  char scan_mode[64];
89  };
90 
91  template <typename T>
92  struct Result
93  {
95  T value;
96  Result(const T& value)
97  : err(SL_RESULT_OK)
98  , value(value)
99  {
100  }
101 
103  : err(err)
104  , value()
105  {
106  }
107 
108  operator sl_result() const
109  {
110  return err;
111  }
112 
113  operator bool() const
114  {
115  return SL_IS_OK(err);
116  }
117 
118  T& operator* ()
119  {
120  return value;
121  }
122 
123  T* operator-> ()
124  {
125  return &value;
126  }
127  };
128 
132  class IChannel
133  {
134  public:
135  virtual ~IChannel() {}
136 
137  public:
141  virtual bool open() = 0;
142 
146  virtual void close() = 0;
147 
151  virtual void flush() = 0;
152 
160  virtual bool waitForData(size_t size, sl_u32 timeoutInMs = -1, size_t* actualReady = nullptr) = 0;
161 
168  virtual int write(const void* data, size_t size) = 0;
169 
176  virtual int read(void* buffer, size_t size) = 0;
177 
181  virtual void clearReadCache() = 0;
182 
183  private:
184 
185  };
186 
191  {
192  public:
193  virtual ~ISerialPortChannel() {}
194 
195  public:
196  virtual void setDTR(bool dtr) = 0;
197  };
198 
207  Result<IChannel*> createSerialPortChannel(const std::string& device, int baudrate);
208 
214  Result<IChannel*> createTcpChannel(const std::string& ip, int port);
215 
221  Result<IChannel*> createUdpChannel(const std::string& ip, int port);
222 
224  {
228  };
229 
234  };
235 
240  {
242 
243  // Desire speed
245 
246  // Max speed
247  sl_u16 max_speed;
248 
249  // Min speed
250  sl_u16 min_speed;
251  };
252 
254  {
255  public:
256  virtual ~ILidarDriver() {}
257 
258  public:
264  virtual sl_result connect(IChannel* channel) = 0;
265 
269  virtual void disconnect() = 0;
270 
274  virtual bool isConnected() = 0;
275 
276  public:
277  enum
278  {
279  DEFAULT_TIMEOUT = 2000
280  };
281 
282  public:
287  virtual sl_result reset(sl_u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;
288 
290  virtual sl_result getAllSupportedScanModes(std::vector<LidarScanMode>& outModes, sl_u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;
291 
293  virtual sl_result getTypicalScanMode(sl_u16& outMode, sl_u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;
294 
301  virtual sl_result startScan(bool force, bool useTypicalScan, sl_u32 options = 0, LidarScanMode* outUsedScanMode = nullptr) = 0;
302 
309  virtual sl_result startScanExpress(bool force, sl_u16 scanMode, sl_u32 options = 0, LidarScanMode* outUsedScanMode = nullptr, sl_u32 timeout = DEFAULT_TIMEOUT) = 0;
310 
317  virtual sl_result getHealth(sl_lidar_response_device_health_t& health, sl_u32 timeout = DEFAULT_TIMEOUT) = 0;
318 
323  virtual sl_result getDeviceInfo(sl_lidar_response_device_info_t& info, sl_u32 timeout = DEFAULT_TIMEOUT) = 0;
324 
330  virtual sl_result checkMotorCtrlSupport(MotorCtrlSupport& motorCtrlSupport, sl_u32 timeout = DEFAULT_TIMEOUT) = 0;
331 
339  virtual sl_result getFrequency(const LidarScanMode& scanMode, const sl_lidar_response_measurement_node_hq_t* nodes, size_t count, float& frequency) = 0;
340 
345  virtual sl_result setLidarIpConf(const sl_lidar_ip_conf_t& conf, sl_u32 timeout = DEFAULT_TIMEOUT) = 0;
346 
350  virtual sl_result getDeviceMacAddr(sl_u8* macAddrArray, sl_u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;
351 
355  virtual sl_result stop(sl_u32 timeout = DEFAULT_TIMEOUT) = 0;
356 
374  virtual sl_result grabScanDataHq(sl_lidar_response_measurement_node_hq_t* nodebuffer, size_t& count, sl_u32 timeout = DEFAULT_TIMEOUT) = 0;
375 
383  virtual sl_result ascendScanData(sl_lidar_response_measurement_node_hq_t* nodebuffer, size_t count) = 0;
384 
392  virtual sl_result getScanDataWithIntervalHq(sl_lidar_response_measurement_node_hq_t* nodebuffer, size_t& count) = 0;
399  virtual sl_result setMotorSpeed(sl_u16 speed = DEFAULT_MOTOR_SPEED) = 0;
400 
404  virtual sl_result getMotorInfo(LidarMotorInfo &motorInfo, sl_u32 timeoutInMs = DEFAULT_TIMEOUT) = 0;
405 
406 
414  virtual sl_result negotiateSerialBaudRate(sl_u32 requiredBaudRate, sl_u32* baudRateDetected = NULL) = 0;
415 };
416 
445 }
Result(const T &value)
Result< IChannel * > createUdpChannel(const std::string &ip, int port)
Definition: sl_crc.h:38
Result(sl_result err)
virtual ~IChannel()
sl_u8 size
sl_result err
MotorCtrlSupport motorCtrlSupport
MotorCtrlSupport
Result< ILidarDriver * > createLidarDriver()
#define DEFAULT_MOTOR_SPEED
Definition: sl_lidar_cmd.h:112
virtual ~ILidarDriver()
#define SL_IS_OK(x)
Definition: sl_types.h:82
Result< IChannel * > createSerialPortChannel(const std::string &device, int baudrate)
uint32_t sl_result
Definition: sl_types.h:69
#define SL_RESULT_OK
Definition: sl_types.h:71
Result< IChannel * > createTcpChannel(const std::string &ip, int port)
sl_u8 data[0]


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