Arduino Mega2560 使用激光雷达测距(RPLidar A1)

实验效果

凌顺实验室(lingshunlab.com)本次分享通过输出全部角度和输出指定角度的距离两种方式,观察测量的前方障碍物的距离。

本次实验,使用了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

注意:型号为A1M8

引脚说明

引脚 说明
TX RPLIDAR 测距核心串口输出
RX RPLIDAR 测距核心串口输入
VCC_5V RPLIDAR 测距核心供电
GND RPLIDAR 测距核心地线
GND_MOTO RPLIDAR 扫描电机地线
CTRL_MOTO RPLIDAR 扫描电机使能/PWM 控制信号(高电平有效)
5V_MOTO RPLIDAR 扫描电机供电

BOM表

名称 数量
Arduino Mega 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库:

// 加载RPLidar库
#include <RPLidar.h>

创建实例:

// 创建一个名为lidar的雷达驱动实例 
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;

程序代码

以下是完整的代码,是在RPlidar的例程simple_connect为基础,进行修改的。

// lingshunlab.com

// This sketch code is based on the RPLIDAR driver library provided by RoboPeak
// include library // 加载库
#include <RPLidar.h>

// 创建一个名为lidar的雷达驱动实例 
RPLidar lidar;

#define RPLIDAR_MOTOR 3   // The PWM pin for control the speed of RPLIDAR's motor.
                          //用于控制 RPLIDAR 电机速度的 PWM 引脚。
                          //This pin should connected with the RPLIDAR's MOTOCTRL
                          // 该引脚应与RPLIDAR的MOTOCTRL信号相连。

void setup() {
  // bind the RPLIDAR driver to the arduino hardware serial
  // 将RPLIDAR驱动与arduino硬件串口绑定。
  lidar.begin(Serial1);
  Serial.begin(115200);

  // set pin modes
  // 设置引脚模式
  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
                                                        //当前测量的质量

    //在这里进行数据处理...
    // - 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 < 2 ){
      Serial.print(angle);
      Serial.print(" | ");
      Serial.println(distance);
    }
  } else {
    analogWrite(RPLIDAR_MOTOR, 0); //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
       // 启动电机以最大允许速度旋转
       analogWrite(RPLIDAR_MOTOR, 255);
       delay(1000);
    }
  }
}