Click the original text to read, better experience with the code.
Experimental Results
Lingshun Laboratory (lingshunlab.com) shares how to connect the RPLidar laser radar (RPLidar A1 A1M8) with ESP32, and output the distance of all angles and specified angles through the serial port, observing the distance of obstacles in front.
This experiment uses ESP32, connecting RPLidar A1 to serial port 2 of ESP32 (Serial2
), and the data is output in the serial port (Serial
), making it easy to observe data changes.
For Arduino Mega2560 using laser radar for distance measurement (RPLidar A1), please refer to: https://lingshunlab.com/book/arduino/arduino-mega2560-use-rplidar-a1
Component Description
Maximum Measurement Range (m) | Maximum Measurement Frequency (Hz) | 360° Scanning Distance Measurement | Applicable Scenarios | Applicable Voltage | Pitch Angle |
---|---|---|---|---|---|
12 | 8000 | Supported | Indoor | 5V | 1° |
RPLIDAR A1 adopts laser triangulation technology, combined with independently developed high-speed visual acquisition and processing mechanisms, capable of performing more than 8000 distance measurements per second.
The core of RPLIDAR A1 rotates clockwise, allowing for 360-degree omnidirectional scanning distance measurement of the surrounding environment, thus obtaining the contour map of the surrounding environment.
It has comprehensively improved the internal optical and algorithm systems, with a sampling frequency of up to 8000 times/second, allowing robots to map faster and more accurately.
Traditional non-solid-state laser radars often use slip rings to transmit energy and data information, but due to mechanical wear, their continuous working life is only a few thousand hours. By integrating wireless power supply and optical communication technology, we have innovatively designed optical-magnetic fusion technology to completely solve the problem of electrical connection failure and short lifespan of laser radar caused by physical contact wear.
The radar scanning frequency can be controlled via motor PWM signal.
The word count is almost enough, for specific details please refer to the official documentation: https://www.slamtec.com/cn/Support#rplidar-a-series
Note: The model is A1M8
Pin Description
Pin | Description |
---|---|
TX | RPLIDAR distance measurement core serial output |
RX | RPLIDAR distance measurement core serial input |
VCC_5V | Power supply for RPLIDAR distance measurement core |
GND | Ground for RPLIDAR distance measurement core |
GND_MOTO | Ground for RPLIDAR scanning motor |
CTRL_MOTO | RPLIDAR scanning motor enable/PWM control signal (high level effective) |
5V_MOTO | Power supply for RPLIDAR scanning motor |
BOM List
Name | Quantity |
---|---|
ESP32 | x1 |
RPLidar A1 360 Laser Scanning Distance Radar | x1 |
Breadboard | x1 |
Jumper Wires (Dupont Wires) | Several |
Wiring Method
ESP32 Pin | <-> | RPLidar A1 Pin |
---|---|---|
16 | <-> | TX |
17 | <-> | RX |
5V | <-> | VCC_5V |
GND | <-> | GND |
GND | <-> | GND_MOTO |
14 | <-> | CTRL_MOTO |
5V | <-> | 5V_MOTO |
Program Tips
First, you need to install the Arduino library for RPlidar developed by RoboPeak, as it is not available in the library manager of the Arduino IDE, so manual installation is required.
The download address is as follows: https://github.com/robopeak/rplidar_arduino
After unzipping, place the “RPLidarDriver” folder in the “libraries” folder under the installation directory of Arduino IDE, and you will be able to use the RPLidar library. If prompted that it cannot be found, please check whether it is installed correctly.
Then you can start programming.
Load the RPLidar Library Just Installed
// Load RPLidar library
#include <RPLidar.h>
Create an Instance:
// Create a radar driver instance named lidar
RPLidar lidar;
Define the PWM Pin for Motor Control:
#define RPLIDAR_MOTOR 3
Bind to the Specified Serial Port:
lidar.begin(Serial1);
Set the Motor Control Pin to Output Mode
pinMode(RPLIDAR_MOTOR, OUTPUT);
Here ESP32 is different from Arduino, ESP32’s PWM control requires a few more lines of code for definition and usage. In this example, the motor control speed is simplified to HIGH and LOW. For those who need ESP32 PWM control, you can check related examples and modify it yourself.
Use the following condition to return whether lidar is working normally
IS_OK(lidar.waitPoint()
Return the Current Distance Value in Millimeters (mm)
float distance = lidar.getCurrentPoint().distance;
Return the Current Angle in Degrees
float angle = lidar.getCurrentPoint().angle;
Return Whether This Point Belongs to a New Scan
bool startBit = lidar.getCurrentPoint().startBit;
Return the Quality of the Current Measurement
byte quality = lidar.getCurrentPoint().quality;
Errors When Compiling the RPLidar Library with ESP32
When selecting the ESP32 development board program, you may encounter the following error during compilation:
In member function ‘bool RPLidar::begin(HardwareSerial&)’
warning: no return statement in function returning non-void [-Wreturn-type]
The general meaning is that the function definition of RPLidar::begin() is defined as a bool return value, but there is no return value in the function.Why is there no prompt when using Arduino series development boards, but there is a prompt when using ESP series development boards?Lingshun Laboratory (lingshunlab.com) believes that the syntax requirements for the ESP series are more stringent.
At this time, we need to modify two files of the RPLidar library, namely RPlidar.h and divRPlidar.cpp, change the definition of the RPLidar::begin() function from bool to void, defining it as a non-return value. The following images are for modification reference:
After recompiling, the error prompt disappears.
Program Code
The following is the complete code, modified based on the RPlidar example simple_connect
.
// lingshunlab.com
// https://lingshunlab.com/book/arduino/esp32-use-rplidar-a1
// This sketch code is based on the RPLIDAR driver library provided by RoboPeak
// include library // Load library
#include <RPLidar.h>
// Create a radar driver instance named lidar
RPLidar lidar;
#define RPLIDAR_MOTOR 14 // Used to control RPLIDAR motor speed. Since ESP32's PWM settings are more complicated,
// it is currently simply controlled using HIGH and LOW.
// This pin should be connected to the RPLIDAR MOTOCTRL signal.
// welcome to lingshunlab.com
void setup() {
Serial.begin(115200);
// bind the RPLIDAR driver to the arduino hardware serial
// Bind the RPLIDAR driver to the ESP32 Serial2 hardware serial.
Serial2.begin(115200, SERIAL_8N1, 16, 17);
while(lidar.begin(Serial2));
// set pin modes
// Set pin modes
pinMode(RPLIDAR_MOTOR, OUTPUT);
delay(1000);
// Start the radar rotation
digitalWrite(RPLIDAR_MOTOR, HIGH);
}
void loop() {
if (IS_OK(lidar.waitPoint())) {
float distance = lidar.getCurrentPoint().distance; //distance value in mm unit
//Distance value in mm unit
float angle = lidar.getCurrentPoint().angle; //angle value in degree
//Angle value in degree
bool startBit = lidar.getCurrentPoint().startBit; //whether this point belongs to a new scan
//Whether this point belongs to a new scan
byte quality = lidar.getCurrentPoint().quality; //quality of the current measurement
//Quality of the current measurement
// Data processing here...
// - 1 -
// Perform data processing here...
// Output all data in the serial port
// Output all data in the serial port
// for(int i = 0;i < 6 - String(angle).length(); i++){
// Serial.print(" ");
// }
// Serial.print(String(angle));
// Serial.print(" | ");
// for(int i = 0;i < 8 - String(distance).length(); i++){
// Serial.print(" ");
// }
// Serial.print(distance);
// Serial.print(" | ");
// Serial.print(startBit);
// Serial.print(" | ");
// for(int i = 0;i < 2 - String(quality).length(); i++){
// Serial.print(" ");
// }
// Serial.println(quality);
// - 2 -
// Output the specified angle data
// Output specified angle
if(angle > 0 and angle < 100 ){
Serial.print(angle);
Serial.print(" | ");
Serial.println(distance);
}
} else {
digitalWrite(RPLIDAR_MOTOR, LOW); //stop the rplidar motor
//Stop the RPLIDAR motor
// try to detect RPLIDAR...
// Try to detect RPLIDAR...
rplidar_response_device_info_t info;
if (IS_OK(lidar.getDeviceInfo(info, 100))) {
// detected...
// Detected...
lidar.startScan();
// start motor rotating at max allowed speed
// Start motor rotating at max allowed speed
digitalWrite(RPLIDAR_MOTOR, HIGH);
delay(1000);
}
}
}
After uploading, you can see the output data at the specified angle.