LD19 is mainly composed of laser ranging core, wireless transmission unit, wireless communication unit, angle measurement unit, motor drive unit and mechanical shell.
中文资料:https://wiki.youyeetoo.cn/zh/LD19
English SDK Download Link:https://drive.google.com/drive/folders/1-7aiv9moeNkiL13mpPsgMKU4E2sX7BYs?usp=sharing
The STL-19P consists mainly of a laser ranging core, a wireless power transmission unit, a wireless communication unit, an angle measuring unit, a motor drive unit and a mechanical housing.
With DTOF technology, STL-19P ranging core is able to perform 5,000 measurements per second. For each ranging, the LiDAR emits an infrared laser, which is reflected back to the single photon receiving unit when it encounters the target object.From this, we obtain the time at which the laser is emitted and that at which it is received by the single photon receiving unit. The time difference between them is the time of flight of the light, which can be combined with the speed of light to solve for the distance.Once the distance data have been obtained, STL-19P fuses the angle values measured by the angle measuring unit to form the point cloud data and then sends the point cloud data to an external interface via wireless communication.Meanwhile the external interface supports PWM input to enable the motor drive unit to drive the motor rotation. The external control unit obtains the speed and controls it to the specified speed by means of a PID algorithm in closed-loop control, thus allowing the LiDAR to work stably.
The diagram of the environmental scan formed by STL-19P point cloud data is shown below:
The product is mainly suitable for the navigation and obstacle avoidance of robots (e.g. floor mopping robots and service robots) by performing a 360° scan of the indoor layout and building a map so that a walking path can be planned. It is also suitable for robotics education and research, etc.
The LD19 uses ZH1.5T-4P 1.5mm connector
to connect with external system to realize power supply and data reception. The specific interface definition and parameter requirements are shown in the following figure/table:
The LD19 has a motor driver with stepless speed regulation, which supports internal speed control and external speed control. Whenthe PWM pin is grounded, the default is internal speed regulation, and the default speed is 10±0.1Hz.
For external speed control, a square wave signal needs to be connected to the PWM pin, and the start, stop and speed of the motor can be controlled through the duty cycle of the PWM signal.
Conditions for triggering external speed control:
a. Input PWM frequency 20-50K, recommended 30K;
b. Duty cycle is within (45%, 55%) interval (excluding 45% and 55%), and at least 100ms continuous input time.
After the external speed control is triggered, it is always in the external speed control state, and the internal speed control will be restored unless the power is turned off and restarted; at the same time, the speed control can be performed by adjusting the PWM duty cycle. Due to the individual differences of each product motor, the actual speed may be different when the duty cycle is set to a typical value. To accurately control the motor speed, it is necessary to perform closed-loop control according to the speed information in the received data.
Note:
When not using external speed control, the PWM pin must be grounded.
The data communication of LD19 adopts standard universal asynchronous serial port (UART) one-way transmission, and its transmission parameters are shown in the following table:
Baud rate | Data length | Stop bit | Parity check bit | Flow control |
---|---|---|---|---|
230400 | 8Bits | 1 | N/A | N/A |
With one-way communication, LD19 starts sending measurement data as soon as the
rotation is stabilized, without sending any commands.
The LD19 adopts one-way communication. After stable operation, it starts to send measurement data packets without sending any commands. The measurement packet format is shown in the figure below.
Value | Description |
---|---|
Header |
The length is 1 Byte, and the value is fixed at 0x54, indicating the beginning of the data packet |
VerLen |
The length is 1 Byte, the upper three bits indicate the packet type, which is currently fixed at 1, and the lower five bits indicate the number of measurement points in a packet, which is currently fixed at 12, so the byte value is fixed at 0x2C; |
Speed |
The length is 2 Byte, the unit is degrees per second, indicating the speed of the lidar; |
Start angle |
The length is 2 Bytes, and the unit is 0.01 degrees, indicating the starting angle of the data packet point; |
Data |
Indicates measurement data, a measurement data length is 3 bytes, please refer to the next section for detailed analysis; |
End angle |
The length is 2 Bytes, and the unit is 0.01 degrees, indicating the end angle of the data packet point; |
Timestamp |
The length is 2 Bytes, the unit is milliseconds, and the maximum is 30000. When it reaches 30000, it will be counted again,ndicating the timestamp value of the data packet; |
CRC check |
The length is 1 Byte, obtained from the verification of all the previous data except itself. For the CRC verification method, see the following content for details; |
The data structure reference is as follows:
#define POINT_PER_PACK 12
#define HEADER 0x54
typedef struct attribute ((packed)) { uint16_t distance;
uint8_t intensity;
} LidarPointStructDef;
typedef struct attribute ((packed)) {
uint8_ t header;
uint8 t ver len;
uint16_ t speed;
uint16_ t start_ _angle;
LidarPointStructDef point[POINT_ PER_ PACK];
uint16_ t end_ angle;
uint16 t timestamp;
uint8_ t crc8;
}LiDARFrameTypeDef;
The CRC check calculation method is as follows:
static const uint8_t CrcTable[256] = {
0x00, 0x4d, 0x9a, 0xd7, 0x79, 0x34, 0xe3, 0xae, 0xf2, 0xbf, 0x68, 0x25,
0x8b, 0xc6, 0x11, 0x5c, 0xa9, 0xe4, 0x33, 0x7e, 0xd0, 0x9d, 0x4a, 0x07,
0x5b, 0x16, 0xc1, 0x8c, 0x22, 0x6f, 0xb8, 0xf5, 0x1f, 0x52, 0x85, 0xc8,
0x66, 0x2b, 0xfc, 0xb1, 0xed, 0xa0, 0x77, 0x3a, 0x94, 0xd9, 0x0e, 0x43,
0xb6, 0xfb, 0x2c, 0x61, 0xcf, 0x82, 0x55, 0x18, 0x44, 0x09, 0xde, 0x93,
0x3d, 0x70, 0xa7, 0xea, 0x3e, 0x73, 0xa4, 0xe9, 0x47, 0x0a, 0xdd, 0x90,
0xcc, 0x81, 0x56, 0x1b, 0xb5, 0xf8, 0x2f, 0x62, 0x97, 0xda, 0x0d, 0x40,
0xee, 0xa3, 0x74, 0x39, 0x65, 0x28, 0xff, 0xb2, 0x1c, 0x51, 0x86, 0xcb,
0x21, 0x6c, 0xbb, 0xf6, 0x58, 0x15, 0xc2, 0x8f, 0xd3, 0x9e, 0x49, 0x04,
0xaa, 0xe7, 0x30, 0x7d, 0x88, 0xc5, 0x12, 0x5f, 0xf1, 0xbc, 0x6b, 0x26,
0x7a, 0x37, 0xe0, 0xad, 0x03, 0x4e, 0x99, 0xd4, 0x7c, 0x31, 0xe6, 0xab,
0x05, 0x48, 0x9f, 0xd2, 0x8e, 0xc3, 0x14, 0x59, 0xf7, 0xba, 0x6d, 0x20,
0xd5, 0x98, 0x4f, 0x02, 0xac, 0xe1, 0x36, 0x7b, 0x27, 0x6a, 0xbd, 0xf0,
0x5e, 0x13, 0xc4, 0x89, 0x63, 0x2e, 0xf9, 0xb4, 0x1a, 0x57, 0x80, 0xcd,
0x91, 0xdc, 0x0b, 0x46, 0xe8, 0xa5, 0x72, 0x3f, 0xca, 0x87, 0x50, 0x1d,
0xb3, 0xfe, 0x29, 0x64, 0x38, 0x75, 0xa2, 0xef, 0x41, 0x0c, 0xdb, 0x96,
0x42, 0x0f, 0xd8, 0x95, 0x3b, 0x76, 0xa1, 0xec, 0xb0, 0xfd, 0x2a, 0x67,
0xc9, 0x84, 0x53, 0x1e, 0xeb, 0xa6, 0x71, 0x3c, 0x92, 0xdf, 0x08, 0x45,
0x19, 0x54, 0x83, 0xce, 0x60, 0x2d, 0xfa, 0xb7, 0x5d, 0x10, 0xc7, 0x8a,
0x24, 0x69, 0xbe, 0xf3, 0xaf, 0xe2, 0x35, 0x78, 0xd6, 0x9b, 0x4c, 0x01,
0xf4, 0xb9, 0x6e, 0x23, 0x8d, 0xc0, 0x17, 0x5a, 0x06, 0x4b, 0x9c, 0xd1,
0x7f, 0x32, 0xe5, 0xa8};
uint8_t CalCRC8(uint8_t *p, uint8_t len){
uint8_t crc = 0;
uint16_t i;
for (i = 0; i < len; i++){
crc = CrcTable[(crc ^ *p++) & 0xff];
}
return crc;
}
Each measurement data point consists of a 2-byte distance value and a 1-byte confidence value, as shown in the figure below.
The unit of distance value is mm. The signal intensity value reflects the light reflection intensity. The higher the intensity, the larger the signal intensity value; the lower the intensity, the smaller the signal intensity value. For a white object within 6m, the typical value of the signal strength value is around 200.
The angle value of each point is obtained by linear interpolation of the starting angle and the ending angle. The angle calculation method is as follows:
The data structure reference is as follows:
step = (end_angle – start_angle)/(len – 1);
angle = start_angle + step*i;
where len is the number of measurement points in a data packet, and the value range of i is [0,len).
Suppose we receive a piece of data as shown below.
54 2C 68 08 AB 7E E0 00 E4 DC 00 E2 D9 00 E5 D5 00 E3 D3 00 E4 D0 00 E9 CD
00 E4 CA 00 E2 C7 00 E9 C5 00 E5 C2 00 E5 C0 00 E5 BE 82 3A 1A 50
We analyze it as follows:
The LD19 uses a left-handed coordinate system, the rotation center is the coordinate origin, the front of the sensor is defined as the zero-degree direction, and the rotation angle increases clockwise, as shown in the figure below.
1.LiDAR, wire, USB adapter board, as shown in the following figure:
2.Connection diagram, as shown in the figure below:
3.Or connect directly to the motherboard or MCU.
When evaluating the company's products under Windows, it is necessary to install the serial port driver of the USB adapter board. The reason is that the USB adapter board in the development kit provided by the company adopts the CP2102 USB to serial port adapter chip, and its driver can be obtained from Silicon Download from Labs' official website:
https://www.silabs.com/developers/usb-to-uart-bridge-vcp-drivers
After decompressing the CP210x_Universal_Windows_Driver driver package, execute the exe file in the driver installation package directory, and select X86 (32-bit) or X64 (64-bit) according to the Windows system version.
Double-click the exe file and follow the prompts to install it.
After the installation is complete, connect the USB adapter board in the development kit to the computer, right-click [My Computer], select [Properties], and in the opened [System] interface, select [Device Manager] in the left menu to enter Go to the device manager, expand [Ports], you can see the serial port number corresponding to the recognized CP2102 USB adapter, that is, the driver is installed successfully, and the figure below is COM4.
We provides the point cloud visualization software desktop for real-time scanning of this product, and developers can use this software to visually observe the scanning renderings of this product. Before using this software, it is necessary to distinguish that the driver of the USB adapter board of this product has been installed successfully, and the product is interconnected with the USB port of the Windows system PC, then double-click the ld_desktop.exe file, and select the corresponding product model and port number, click the Start point cloud refresh button, as shown in the following figure.
ROS (Robot Operating System) is an open source meta-operating system for robots and middleware built on Linux. It provides the services expected of an operating system, including hardware abstraction, low-level device control, implementation of commonly used functions, message passing between processes, and package management. It also provides the tools and library functions needed to obtain, compile, write, and run code across computers. For the installation steps of each version of ROS, please refer to the official ROS website:
http://wiki.ros.org/ROS/Installation
The ROS function package of this product supports the following versions and environments:
ROS Kinetic(Ubuntu16.04);
ROS Melodic(Ubuntu18.04);
ROS Noetic(Ubuntu20.04).
First, connect the lidar to our adapter module (CP2102 adapter), and connect the module to the computer. Then, open a terminal under the ubuntu system and enter ls /dev/ttyUSB* to check whether the serial device is connected. If a serial port device is detected, use the sudo chmod 777 /dev/ttyUSB* command to give it the highest authority, that is, give the file owner, group, and other users read, write and execute permissions, as shown in the following figure.
Finally, modify the port_name value in the ld19.launch file in the
~/ldldiar_ros_ws/src/ldlidar_stl_ros/launch/ directory. Take the lidar mounted in the
system as /dev/ttyUSB0 as an example, as shown below.
$ nano ~/ldlidar_ros_ws/src/ldldiar_stl_ros/launch/ld19.launch
Linux nano editor: Ctrl + O saves the edited file; Ctrl + X exits the editing interface.
1.Use the catkin compilation system to compile and build the product function package:
$ cd ~/ldlidar_ros_ws
$ catkin_make
2.Function package environment variable settings:
After the compilation is completed, you need to add the relevant files generated by the compilation to the environment variables, so that the ROS environment can recognize them. The execution command is as follows. This command is to temporarily add environment variables to the terminal, which means that if you reopen a new terminal, you also need to re-execute it. The following command.
$ cd ~/ldlidar_ros_ws
$ source devel/setup.bash
In order to never need to execute the above command to add environment variables after reopening the terminal, you can do the following.
$ echo “source ~/ldlidar_ros_ws/devel/setup.bash” >> ~/.bashrc
$ source ~/.bashrc
Use the roslaunch tool to start the lidar node and execute the following command.
$ roslaunch ldlidar_stl_ros ld19.launch
Rviz is a 3D visualization tool in the ROS framework, where lidar data can be displayed. After roslaunch successfully runs the lidar node, open a new terminal (Ctrl+Alt+T) and enter the following command:
$ rosrun rviz rviz
After the interface starts, click file->open->Config in the menu bar of the interface, then select: ldlidar.rviz file in the ~/ldlidar_ros_ws/src/ldlidar_stl_ros/rviz/ directory, open the configuration file ldlidar.rviz, and click LaserScan Select
/LiDAR/LD19 in the Topic.
Since the point cloud data of our lidar product follows the left-handed coordinate system (clockwise), and Rviz shows that the radar point cloud data follows the right-handed coordinate system (counterclockwise), we performed the product point cloud data in the function package source code toLaserScan function. The coordinate system is transformed so that it can display the point cloud normally in Rviz.
ROS (Robot Operating System) is an open source meta-operating system for robots and middleware built on Linux. It provides the services expected of an operating system, including hardware abstraction, low-level device control, implementation of commonly used functions, message passing between processes, and package management. It also provides the tools and library functions needed to obtain, compile, write, and run code across computers. The robotics and ROS community has changed a lot since ROS was launched in 2007. The goal of the ROS2 project is to adapt to these changes, leveraging the strengths of ROS1 and improving on the weaknesses. For the installation steps of ROS2, please refer to the official website of ROS2:https://docs.ros.org/en/foxy/Installation.html
The ROS2 function package of this product supports the use of the ROS2 Foxy (Ubuntu20.04) version environment.
First, connect the lidar to our adapter module (CP2102 adapter), and connect the module to the computer. Then, open a terminal under the ubuntu system and enter ls /dev/ttyUSB* to check whether the serial device is connected. If a serial port device is detected, use the sudo chmod 777 /dev/ttyUSB* command to give it the highest authority, that is, give the file owner, group, and other users read, write and execute permissions, as shown in the following figure.
Finally, modify the port_name value in the ld19.launch file in the
~/ldldiar_ros_ws/src/ldlidar_stl_ros/launch/ directory. Take the lidar mounted in the
system as /dev/ttyUSB0 as an example, as shown below.
$ nano ~/ldlidar_ros2_ws/src/ldldiar_stl_ros2/launch/ld19.launch.py
Linux nano editor: Ctrl + O saves the edited file; Ctrl + X exits the editing interface.
1.Use the catkin compilation system to compile and build the product function package:
$ cd ~/ldlidar_ros2_ws
$ colcon build
2.Function package environment variable settings:
After the compilation is completed, you need to add the relevant files generated by the compilation to the environment variables, so that the ROS environment can recognize them. The execution command is as follows. This command is to temporarily add environment variables to the terminal, which means that if you reopen a new terminal, you also need to re-execute it. The following command.
$ cd ~/ldlidar_ros2_ws
$ source install/setup.bash
In order to never need to execute the above command to add environment variables after reopening the terminal, you can do the following.
$ echo “source ~/ldlidar_ros2_ws/install/setup.bash” >> ~/.bashrc
$ source ~/.bashrc
Use the roslaunch tool to start the lidar node and execute the following command.
$ ros2 launch ldlidar_stl_ros2 ld19.launch.py
Rviz2 is a 3D visualization tool in the ROS2 framework, where lidar data can be displayed. After ros2 launch successfully runs the lidar node, open a new terminal (Ctrl+Alt+T) and enter the following command:
$ rviz2
After the interface is started, click file->open->Config in the menu bar of the interface, and then select: ldlidar.rviz file in the
~/ldlidar_ros2_ws/src/ldlidar_stl_ros2/rviz2/ directory, open the configuration file ldlidar.rviz, and click LaserScan Select /LiDAR/LD19 in the Topic.
Since the point cloud data of our radar product follows the left-handed coordinate system (clockwise), and Rviz2 shows that the lidar point cloud data follows the right-handed coordinate system (counterclockwise), we performed the product point cloud data in the function package source code toLaserScan function. The coordinate system is transformed so that it can display the point cloud normally in Rviz2.
First, connect the lidar to our adapter module (CP2102 adapter), and connect the module to the computer. Then, open a terminal under the ubuntu system andenter ls /dev/ttyUSB* to check whether the serial device is connected. If a serial port device is detected, use the sudo chmod 777 /dev/ttyUSB* command to give it the highest authority, that is, give the file owner,group, and other users read, write and execute permissions, as shown in the following figure.
The source code is coded in C++11 standard C++ language and C99 standard C language. Use CMake, GNU-make, GCC and other tools to compile and build the source code. If you use Ubuntu system without the above tools installed, you can execute the following command to complete the installation.
$ sudo apt-get install build-essential cmake
If the tools indicated above already exist in the system, do the following.
$ cd ~/ldlidar_ws/ldlidar_stl_sdk
# If the build folder does not exist in the ldlidar_stl_sdk directory, it needs to be created
$ mkdir build
$ cd build
$ cmake ../
$ make
$ cd ~/ldlidar_ws/ldlidar_stl_sdk/build
$ ./ldlidar_stl <serial_number>
# eg: ./ldlidar_stl /dev/ttyUSB0
Please refer to the manual 《 Raspberry Pi Raspbian User manual.pdf》 for details. This manual applies to our company's product models LD06 and LD19
Raspberry Pi Raspbian User manual.pdf
Web:https://www.youyeetoo.com/
Forum:https://forum.youyeetoo.com/
amazon: https://www.amazon.com/youyeetoo
blog: https://youyeetoo.com/blog/
[cn web]:https://youyeetoo.cn/
aliexpress:https://smartfire.aliexpress.com/store/1100924668
Customized service:peter@youyeetoo.com