使用了Arduino Mega 2560,這是因為Mega 2560有多個串口,RPLidar A1 連接串口1(Serial1),數據在串口(Serial)中輸出,這樣就可以方便觀察數據變化。

當然,使用Arduino Uno 進行實驗也可以的,但只有一個硬串口,要觀察數據則需要增加螢幕或者LED,才能得知數據變化。接線類似的,但電機(5V_MOTO, GND_MOTO)也許需要另外供電才比較穩定。

元件說明

最大測量範圍(m) 最大測量頻率(Hz) 360°掃描測距 適用場景 適用電壓 俯仰角度
12 8000 支持 室內 5V

 

RPLIDAR A1採用激光三角測距技術,配合自主研發的高速的視覺採集處理機構, 可進行每秒8000次以上的測距動作。RPLIDAR A1 的測距核心順時針旋轉,可實現對周圍環境的360度全方位掃描測距檢測,

從而獲得周圍環境的輪廓圖。全面改進了內部光學和算法系統, 採樣頻率高達8000次/秒,讓機器人能更快速、精確的建圖。傳統的非固態激光雷達多采用滑環傳輸能量和數據信息,

但由於存在機械磨損,其連續工作時僅有數千小時壽命。綜合無線供電和光通信技術,獨創性的設計了光磁融合技術徹底解決了因物理接觸磨損導致電氣連接失效、激光雷達壽命短的問題可通過電機PWM信號控制雷達掃描頻率

具體詳細請參考官方文檔:https://www.slamtec.com/cn/Support#rplidar-a-series

腳位說明

引腳 說明
TX RPLIDAR 串口輸出
RX RPLIDAR 串口輸入
VCC_5V RPLIDAR 供電
GND RPLIDAR 地線
GND_MOTO RPLIDAR 地線
CTRL_MOTO RPLIDAR 馬達PWM控制
5V_MOTO RPLIDAR 馬達供電

材料清單

名稱 數量

Arduino Mega 2560

x1

RPLidar A1 360 激光掃描測距雷達

x1
麵包板 x1
跳線(杜邦線) 若干

接線方式

 

Arduino Mega 引腳 <-> RPLidar A1 引腳
RX1 <-> TX
TX1 <-> RX
5V <-> VCC_5V
GND <-> GND
GND <-> GND_MOTO
Pin 3 <-> CTRL_MOTO
5V <-> 5V_MOTO

程式重點

首先,需要安裝RoboPeak開發的RPlidar的Arduino庫,由於在Arduino IDE的庫管理中沒有,所以需要手動安裝。下載地址如下: https://github.com/robopeak/rplidar_arduino

解壓後,把「RPLidarDriver」文件夾,放在Arduino IDE 的安裝目錄下的「libraries」文件夾中,就可以使用RPLiadar的庫,如果提示找不到,請重新檢查是否安裝正確。然後就可以開始編程了

加載剛安裝的RPLidar庫:

#include <RPLidar.h>

創建實例:

RPLidar lidar;

定義控制電機的PWM引腳:

#define RPLIDAR_MOTOR 3 

綁定指定串口:

lidar.begin(Serial1);

設置控制電機的PWM引腳為輸出模式

pinMode(RPLIDAR_MOTOR, OUTPUT);

使用以下判斷可以返回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;
程式碼
// lingshunlab.com
// This sketch code is based on the RPLIDAR driver library provided by RoboPeak
// include library
#include <RPLidar.h>

RPLidar lidar;

#define RPLIDAR_MOTOR 3 

void setup() {
  lidar.begin(Serial1);
  Serial.begin(115200);
  pinMode(RPLIDAR_MOTOR, OUTPUT);
}

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


    // 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 < 2 ){
      Serial.print(angle);
      Serial.print(" | ");
      Serial.println(distance);
    }
  } else {
    analogWrite(RPLIDAR_MOTOR, 0); //stop the rplidar motor

    // try to detect RPLIDAR...
    rplidar_response_device_info_t info;
    if (IS_OK(lidar.getDeviceInfo(info, 100))) {
       // detected...
       lidar.startScan();

       // start motor rotating at max allowed speed
       analogWrite(RPLIDAR_MOTOR, 255);
       delay(1000);
    }
  }
}

參考文獻從網路取材