跳转至

VP100L 激光雷达使用说明

Hint

操作环境及软硬件配置如下:

  • 雷达型号:VP100L
  • 通信方式:USB 转串口
  • 推荐系统:Ubuntu 22.04 + ROS2 Humble
  • ROS2 功能包:vp100_ros2
  • 雷达输出话题:/scan
  • 消息类型:sensor_msgs/msg/LaserScan
Attation

VP100L 的串口波特率应设置为 230400。如果波特率设置错误,节点可能可以启动,但无法正常输出 /scan 数据。

功能包/资料包下载链接:(可参考套件资料/资料链接下载)

一、场景说明

VP100L 激光雷达可用于机器人避障、建图、导航、区域检测等场景。ROS2 驱动启动后,会将雷达扫描数据发布为标准 LaserScan 话题,后续可接入 RViz2、SLAM、Nav2 或自定义避障节点使用。

典型数据链路如下:

VP100L 雷达
   ↓ USB/串口
vp100_ros2_node
   ↓ /scan
RViz2 / SLAM / Nav2 / 其他节点

二、VP100L 主要参数

参数名称 单位 典型值 / 范围 说明
测距精度,白靶 80% 反射率 mm ±15mm @ 0.1m-0.5m,STD 3mm;±20mm @ 0.5m-2m,STD 4mm;±30mm @ 2m-12m,STD 15mm 白色高反射目标
测距精度,黑靶 4% 反射率 mm ±20mm @ 0.1m-0.5m,STD 10mm;±40mm @ 0.5m-6m,STD 15mm 黑色低反射目标
扫描频率 Hz 6 固定频率
测距频率 Hz 3000 固定频率
俯仰角误差 ° 0.5 - 1.5 机械安装会影响实际效果
偏航角误差 ° -2 - 2 可通过安装修正或软件角度偏移修正
角度分辨率 ° 0.72 每圈约 500 个扫描点
抗环境光 Klux ≤ 60 强光环境下建议实测确认
整机寿命 H ≥ 1500 按资料参数
整机电流 mA 350 典型工作电流
工作温度 -10 - 45 超出范围可能影响测距稳定性
存储温度 -30 - 70 存储环境要求
激光波长 nm 895 - 915,典型 905 红外波段
激光峰值功率 W 2 激光峰值功率
激光安全等级 - IEC-60825 Class 1 正常使用下为 Class 1 安全等级

三、硬件连接与串口检测

第一步:连接雷达

将 VP100L 雷达通过 USB 转串口线连接到 Ubuntu 主机或机器人主控板。连接后,系统通常会生成类似 /dev/ttyUSB0 的串口设备。

在终端中查看串口设备:

ls /dev/ttyUSB*

也可以查看 USB 设备信息:

lsusb

查看插拔日志:

dmesg -w

插入雷达后,如果看到 ttyUSB0ttyUSB1 或类似串口设备,说明系统已经识别到 USB 转串口设备。

第二步:配置串口权限

如果启动节点时报串口权限错误,例如 Permission denied,可临时赋权:

sudo chmod 666 /dev/ttyUSB0

也可以将当前用户加入 dialout 组,长期生效:

sudo usermod -aG dialout $USER
sudo reboot
Attation

执行 usermod 后需要重新登录或重启系统,否则权限可能不会立即生效。

第三步:固定雷达设备名(可选)

如果机器人上同时接了底盘、机械臂、雷达等多个串口设备,/dev/ttyUSB0 的编号可能会变化。驱动包中提供了 udev 脚本,可将雷达固定为 /dev/nvilidar

进入功能包目录后执行:

cd ~/vp100_ros2_ws/src/vp100_ros2
chmod 0777 startup/*
sudo sh startup/initenv.sh

执行完成后,重新插拔雷达,再查看设备名:

ls -l /dev/nvilidar

如果能看到 /dev/nvilidar,后续参数文件中可将串口名改为:

serialport_name: "/dev/nvilidar"

四、ROS2 功能包说明

压缩包中的 ROS2 驱动包名称为:

vp100_ros2

主要目录结构如下:

vp100_ros2/
├── CMakeLists.txt
├── package.xml
├── launch/
│   ├── vp100_launch.py          # 启动雷达驱动
│   ├── vp100_launch_view.py     # 启动雷达驱动 + RViz2
│   ├── vp100.rviz               # RViz2 配置文件
├── params/
│   └── vp100.yaml               # 雷达参数配置
├── sdk/
│   └── ...                      # 雷达 SDK 和串口通信源码
├── src/
│   ├── vp100_ros2_node.cpp      # 雷达 ROS2 发布节点
│   └── vp100_ros2_client.cpp    # /scan 话题测试客户端
└── startup/
    └── initenv.sh               # udev 固定设备名脚本

驱动节点启动后会发布 /scan 话题,供 RViz2、SLAM、Nav2 或其他 ROS2 节点使用。

五、编译功能包

第一步:创建工作空间

mkdir -p ~/vp100_ros2_ws/src
cd ~/vp100_ros2_ws/src

vp100_ros2 文件夹复制到 src 目录下:

cp -r /path/to/vp100_ros2 ~/vp100_ros2_ws/src/

其中 /path/to/vp100_ros2 请替换为实际解压后的路径。

第二步:安装依赖

sudo apt update
sudo apt install -y \
  ros-humble-rclcpp \
  ros-humble-sensor-msgs \
  ros-humble-visualization-msgs \
  ros-humble-geometry-msgs \
  ros-humble-std-srvs \
  ros-humble-tf2-ros \
  ros-humble-rviz2 \
  python3-colcon-common-extensions

第三步:编译驱动

cd ~/vp100_ros2_ws
source /opt/ros/humble/setup.bash
colcon build --symlink-install --packages-select vp100_ros2

编译完成后加载环境变量:

source ~/vp100_ros2_ws/install/setup.bash

建议加入 ~/.bashrc,以后打开终端自动生效:

echo "source ~/vp100_ros2_ws/install/setup.bash" >> ~/.bashrc
source ~/.bashrc

六、修改 VP100L 参数

参数文件路径:

~/vp100_ros2_ws/src/vp100_ros2/params/vp100.yaml

VP100L 推荐配置如下:

vp100_ros2_node:
  ros__parameters:
    serialport_name: "/dev/ttyUSB0"
    serialport_baud: 230400
    frame_id: "laser_frame"
    resolution_fixed: false
    auto_reconnect: true
    reversion: false
    inverted: false
    angle_min: -180.0
    angle_max: 180.0
    range_min: 0.001
    range_max: 64.0
    aim_speed: 6.0
    sampling_rate: 3
    angle_offset_change_flag: false
    angle_offset: 0.0
    ignore_array_string: ""
    log_enable_flag: true
Attation

原始参数文件中 frame_id 可能为 laser_link,而 launch 文件中的静态 TF 默认发布的是 base_link -> laser_frame

为了避免 RViz2 中出现 No transform from [laser_link] to [laser_frame] 或无法显示雷达数据,建议将 frame_id 统一改为 laser_frame

如果已经使用 udev 固定设备名,则将串口名改为:

serialport_name: "/dev/nvilidar"

七、启动步骤

本示例建议开启两个终端:第一个终端启动雷达驱动,第二个终端查看话题或打开 RViz2。

第一步:启动雷达驱动

打开第一个终端:

cd ~/vp100_ros2_ws
source install/setup.bash
ros2 launch vp100_ros2 vp100_launch.py

启动成功后,终端会打印 VP100 驱动版本信息,并开始连接雷达。

如果雷达串口、波特率和权限配置正确,会持续发布 /scan 数据。

第二步:查看话题是否存在

打开第二个终端:

cd ~/vp100_ros2_ws
source install/setup.bash
ros2 topic list

正常情况下应能看到:

/scan

查看 /scan 数据:

ros2 topic echo /scan

查看发布频率:

ros2 topic hz /scan

VP100L 标称扫描频率为 6Hz,实际频率应接近该值。

第三步:使用测试客户端查看数据

驱动包内提供了一个简单的 /scan 订阅测试程序:

ros2 run vp100_ros2 vp100_ros2_client

该程序会打印角度和距离信息,适合快速确认雷达是否正在输出有效扫描点。

第四步:使用 RViz2 显示雷达点云

方式一:单独打开 RViz2:

rviz2

在 RViz2 中设置:

Fixed Frame: laser_frame
Add -> LaserScan -> Topic: /scan

方式二:使用驱动包自带可视化 launch:

ros2 launch vp100_ros2 vp100_launch_view.py
Attation

如果 vp100_launch_view.py 在 ROS2 Humble 下启动报 node_executable 参数错误,可打开该文件,将:

node_executable='vp100_ros2_node'

修改为:

executable='vp100_ros2_node'

修改后重新编译或重新 source 工作空间即可。

八、参数说明

参数名 推荐值 说明
serialport_name /dev/ttyUSB0/dev/nvilidar 雷达串口设备名
serialport_baud 230400 VP100L 波特率,必须正确
frame_id laser_frame /scan 消息中的坐标系名称
resolution_fixed false 是否固定每圈输出点数
auto_reconnect true 雷达断开后是否自动重连
reversion false 扫描方向反转
inverted false 数据方向翻转
angle_min -180.0 最小扫描角度
angle_max 180.0 最大扫描角度
range_min 0.001 最小有效测距
range_max 64.0 最大有效测距上限,实际有效距离以雷达型号为准
aim_speed 6.0 目标扫描频率,VP100L 固定约 6Hz
sampling_rate 3 采样率,对应 3000 点/秒
angle_offset_change_flag false 是否启用角度偏移
angle_offset 0.0 角度偏移值
ignore_array_string "" 过滤指定角度区间
log_enable_flag true 是否开启日志输出

角度过滤示例:

ignore_array_string: "30,60,90,120"

含义为过滤 30°-60° 和 90°-120° 两段角度范围内的点。

如果将 VP100L 用于机器人导航,建议统一坐标系:

base_link  ->  laser_frame

驱动 launch 中已经包含静态 TF:

base_link 到 laser_frame,Z 方向偏移 0.02m

如果雷达实际安装位置不同,应修改 vp100_launch.pystatic_transform_publisher 的参数:

arguments=['0', '0', '0.02', '0', '0', '0', '1', 'base_link', 'laser_frame']

参数顺序为:

x y z qx qy qz qw parent_frame child_frame

例如雷达安装在机器人前方 0.12m、高度 0.08m,可改为:

arguments=['0.12', '0', '0.08', '0', '0', '0', '1', 'base_link', 'laser_frame']
Attation

Nav2、SLAM 和 RViz2 对 TF 非常敏感。/scanframe_id 必须能通过 TF 树转换到 base_linkodommap,否则会出现有话题但无法显示、建图漂移或导航无法使用的问题。

十、快速验证命令汇总

# 1. 查看串口
ls /dev/ttyUSB*

# 2. 给串口临时权限
sudo chmod 666 /dev/ttyUSB0

# 3. 编译
cd ~/vp100_ros2_ws
source /opt/ros/humble/setup.bash
colcon build --symlink-install --packages-select vp100_ros2
source install/setup.bash

# 4. 启动雷达
ros2 launch vp100_ros2 vp100_launch.py

# 5. 查看话题
ros2 topic list
ros2 topic echo /scan
ros2 topic hz /scan

# 6. RViz2 显示
rviz2

十一、推荐最终配置

如果只用于 VP100L,建议最终将 params/vp100.yaml 保持为:

vp100_ros2_node:
  ros__parameters:
    serialport_name: "/dev/nvilidar"
    serialport_baud: 230400
    frame_id: "laser_frame"
    resolution_fixed: false
    auto_reconnect: true
    reversion: false
    inverted: false
    angle_min: -180.0
    angle_max: 180.0
    range_min: 0.001
    range_max: 64.0
    aim_speed: 6.0
    sampling_rate: 3
    angle_offset_change_flag: false
    angle_offset: 0.0
    ignore_array_string: ""
    log_enable_flag: true

这样可以避免串口编号变化、波特率错误、RViz2 坐标系不匹配等常见问题。

图片1