實驗效果
凌順實驗室(lingshunlab.com)本次分享如何用ESP32連通RPLidar激光雷達(RPLidar A1 A1M8),并且通過串口輸出全部角度和輸出指定角度的距離兩種方式,觀察測量的前方障礙物的距離。
本次實驗,使用ESP32,RPLidar A1 連接ESP32的串口2(Serial2),數據在串口(Serial)中輸出,這樣就可以方便觀察數據變化。
元件說明
最大測量范圍(m) | 最大測量頻率(Hz) | 360°掃描測距 | 適用場景 | 適用電壓 | 俯仰角度 |
---|---|---|---|---|---|
12 | 8000 | 支持 | 室內 | 5V | 1° |
RPLIDAR A1采用激光三角測距技術,配合自主研發的高速的視覺采集處理機構, 可進行每秒8000次以上的測距動作。
RPLIDAR A1 的測距核心順時針旋轉,可實現對周圍環境的360度全方位掃描測距檢測, 從而獲得周圍環境的輪廓圖。
全面改進了內部光學和算法系統, 采樣頻率高達8000次/秒,讓機器人能更快速、精確的建圖。
傳統的非固態激光雷達多采用滑環傳輸能量和數據信息,但由于存在機械磨損,其連續工作時僅有數千小時壽命。綜合無線供電和光通信技術,獨創性的設計了光磁融合技術徹底解決了因物理接觸磨損導致電氣連接失效、激光雷達壽命短的問題
注意:型號為A1M8
引腳說明
引腳 | 說明 |
---|---|
TX | RPLIDAR 測距核心串口輸出 |
RX | RPLIDAR 測距核心串口輸入 |
VCC_5V | RPLIDAR 測距核心供電 |
GND | RPLIDAR 測距核心地線 |
GND_MOTO | RPLIDAR 掃描電機地線 |
CTRL_MOTO | RPLIDAR 掃描電機使能/PWM 控制信號(高電平有效) |
5V_MOTO | RPLIDAR 掃描電機供電 |
BOM表
名稱 | 數量 |
---|---|
ESP32 | x1 |
RPLidar A1 360 激光掃描測距雷達 | x1 |
面包板 | x1 |
跳線(杜邦線) | 若干 |
接線方式
ESP32 引腳 | <-> | RPLidar A1 引腳 |
---|---|---|
16 | <-> | TX |
17 | <-> | RX |
5V | <-> | VCC_5V |
GND | <-> | GND |
GND | <-> | GND_MOTO |
14 | <-> | CTRL_MOTO |
5V | <-> | 5V_MOTO |
程序提點
首先,需要安裝RoboPeak開發的RPlidar的Arduino庫,由于在Arduino IDE的庫管理中沒有,所以需要手動安裝。
解壓后,把「RPLidarDriver」文件夾,放在Arduino IDE 的安裝目錄下的「libraries」文件夾中,就可以使用RPLiadar的庫,如果提示找不到,請重新檢查是否安裝正確。
然后就可以開始編程了
加載剛安裝的RPLidar庫
// 加載RPLidar庫 #include
創建實例:
// 創建一個名為lidar的雷達驅動實例 RPLidar lidar;
定義控制電機的PWM引腳:
#define RPLIDAR_MOTOR 3
綁定指定串口:
lidar.begin(Serial1);
設置控制電機的引腳為輸出模式
pinMode(RPLIDAR_MOTOR, OUTPUT);
這里ESP32和Arduino 不一樣,ESP32的PWM控制需要多幾行代碼進行定義和使用,在這次示例中,簡化了這個電機的控制速度,為HIGH,LOW控制。需要ESP32 PWM控制的,可以查看相關例子,然后自己進行修改。
使用以下判斷可以返回lidar是否正常工作的值
IS_OK(lidar.waitPoint()
返回當前距離值,以毫米(mm)為單位
float distance = lidar.getCurrentPoint().distance;
返回當前角度度數
float angle = lidar.getCurrentPoint().angle;
返回該點是否屬于一個新的掃描點
bool startBit = lidar.getCurrentPoint().startBit;
返回當前測量的質量
byte quality = lidar.getCurrentPoint().quality;
ESP32編譯RPLidar庫時出現的錯誤
選擇使用ESP32開發板程序時,在編譯過程中,可能會出現如下錯誤:
In member function 'bool RPLidar::begin(HardwareSerial&)'
warning: no return statement in function returning non-void [-Wreturn-type]
大概意思是RPLidar::begin()這個函數定義了是bool的返回值,但在函數里面卻沒有返回值。
為什么在使用Arduino 系列開發板沒有提示,而在ESP系列開發板會有提示?凌順實驗室(lingshunlab.com)大概認為是,語法要求ESP系列是比較嚴謹一些。
這時,我們要修改一下RPLidar庫的兩個文件,分別是RPlidar.h和divRPlidar.cpp,把RPLidar::begin()函數的定義bool>RPlidar.cpp,把RPLidar::begin()函數的定義bool>RPlidar.cpp,把RPLidar::begin()函數的定義bool 改成 void ,定義為無返回值即可,以下圖片是修改參考:
再次編譯,錯誤提示消失。
以下是完整的代碼,是在RPlidar的例程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 // 加載庫 #include// 創建一個名為lidar的雷達驅動實例 RPLidar lidar; #define RPLIDAR_MOTOR 14 // 用于控制 RPLIDAR 電機速度。因為ESP32的PWM設置較復雜, // 現在只是簡單使用HIGH,LOW進行控制 // 該引腳應與RPLIDAR的MOTOCTRL信號相連。 // welcome to lingshunlab.com void setup() { Serial.begin(115200); // bind the RPLIDAR driver to the arduino hardware serial // 將RPLIDAR驅動與ESP32 的 Serial2 硬件串口綁定。 Serial2.begin(115200, SERIAL_8N1, 16, 17); while(lidar.begin(Serial2)); // set pin modes // 設置引腳模式 pinMode(RPLIDAR_MOTOR, OUTPUT); delay(1000); // 啟動雷達轉動 digitalWrite(RPLIDAR_MOTOR, HIGH); } void loop() { if (IS_OK(lidar.waitPoint())) { float distance = lidar.getCurrentPoint().distance; //distance value in mm unit //距離值以毫米為單位 float angle = lidar.getCurrentPoint().angle; //anglue value in degree //度數的角度值 bool startBit = lidar.getCurrentPoint().startBit; //whether this point is belong to a new scan //該點是否屬于一個新的掃描點 byte quality = lidar.getCurrentPoint().quality; //quality of the current measurement //當前測量的質量 //在這里進行數據處理... // - 1 - // perform data processing here... // 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 // 輸出指定角度 if(angle > 0 and angle < 100 ){ Serial.print(angle); Serial.print(" | "); Serial.println(distance); } } else { digitalWrite(RPLIDAR_MOTOR, LOW); //stop the rplidar motor //停止rplidar馬達 // try to detect RPLIDAR... // 嘗試檢測RPLIDAR... rplidar_response_device_info_t info; if (IS_OK(lidar.getDeviceInfo(info, 100))) { // detected... // 檢測到 lidar.startScan(); // start motor rotating at max allowed speed // 啟動電機以最大允許速度旋轉 digitalWrite(RPLIDAR_MOTOR, HIGH); delay(1000); } } }
上傳完成后,可以看到指定角度輸出的數據。
審核編輯:劉清
-
激光雷達
+關注
關注
967文章
3938瀏覽量
189593 -
無線供電
+關注
關注
14文章
97瀏覽量
50914 -
RPLIDAR
+關注
關注
0文章
7瀏覽量
7731 -
ESP32
+關注
關注
17文章
957瀏覽量
17082
原文標題:ESP32 使用RPLidar激光雷達測距(RPLidar A1 A1M8)
文章出處:【微信號:凌順實驗室,微信公眾號:凌順實驗室】歡迎添加關注!文章轉載請注明出處。
發布評論請先 登錄
相關推薦
評論