Skip to content

激光雷达数据 rviz2 化处理

激光雷达:LD19 型号;Python 版本:3.8.10;ROS2 版本:humble。

  • 实现步骤:
    • 👉 封装成 ROS2 的 LaserScan 消息
    • 👉 发布成一个 ROS2 Topic
    • 👉 用 rviz2 显示

一、现状分析

上一篇文档中的程序是这样的:

串口 → parse_data() → print()

要改成:

串口 → parse_data()
      → 转换成 LaserScan 消息
      → 发布到 /scan
      → rviz2 显示

当前状态:

✅ 串口雷达数据
✅ Python 解析
⬜ ROS2 LaserScan
⬜ rviz2 显示
⬜ slam_toolbox
⬜ 建图

二、需要了解 3 个 ROS2 关键概念

1️⃣ LaserScan 消息类型

ROS2 中雷达标准消息是:

bash
sensor_msgs/msg/LaserScan

里面包含:

  • angle_min
  • angle_max
  • angle_increment
  • ranges[] (距离数组,单位:米)
  • frame_id

rviz2 就是靠这个显示雷达点云的。

2️⃣ 你要写一个 ROS2 Node(Python)

基本结构:

python
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import LaserScan

3️⃣ rviz2 订阅 /scan 话题

只要你发布的是 LaserScan:

bash
ros2 topic list

看到:

/scan

rviz2 添加:

LaserScan
Topic: /scan

就能看到点云。

三、代码实现

python
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import LaserScan
import serial
import time
import math

class LidarNode(Node):
    def __init__(self):
        super().__init__('lidar_node')

        self.publisher_ = self.create_publisher(LaserScan, '/scan', 10)

        self.ser = serial.Serial(
            port="/dev/ttyACM0",
            baudrate=230400,
            timeout=1
        )

        self.last_angle = 0
        self.get_logger().info("雷达节点启动成功")

        self.timer = self.create_timer(0.01, self.read_lidar)

    def parse_data(self, data):
        speed = data[1] * 256 + data[0]
        start_angle = (data[3] * 256 + data[2]) / 100.0

        points = []
        for x in range(4, 40, 3):
            distance = data[x+1] * 256 + data[x]
            points.append(distance)

        end_angle = (data[41] * 256 + data[40]) / 100.0
        return start_angle, end_angle, points

    def read_lidar(self):
        data = self.ser.read(1)
        if len(data) == 0:
            return

        if data[0] == 0x54:
            data2 = self.ser.read(1)
            if data2[0] == 0x2C:
                data_rest = self.ser.read(45)
                if len(data_rest) < 45:
                    return

                start_angle, end_angle, distances = self.parse_data(data_rest)

                scan = LaserScan()
                scan.header.stamp = self.get_clock().now().to_msg()
                scan.header.frame_id = "laser_frame"

                scan.angle_min = math.radians(start_angle)
                scan.angle_max = math.radians(end_angle)

                scan.angle_increment = (scan.angle_max - scan.angle_min) / len(distances)

                scan.range_min = 0.05
                scan.range_max = 12.0

                scan.ranges = [d / 1000.0 for d in distances]  # mm -> m

                self.publisher_.publish(scan)

def main(args=None):
    rclpy.init(args=args)
    node = LidarNode()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()

四、运行步骤

1️⃣ source ROS2

bash
source /opt/ros/humble/setup.bash

2️⃣ 运行你的节点

bash
python3 lidar_node.py

你应该看到:

雷达节点启动成功

截图代码运行命令为:python3 v2.py,但是代码与前文保持一致。 An image

3️⃣ 打开 rviz2

bash
rviz2

An image

在 rviz2 中:

  • Fixed Frame: laser_frame
  • Add → LaserScan
  • Topic: /scan

如果一切正常,你会看到:

🎉🎉🎉 雷达点云在转!

设置 Fixed Frame: laser_frame,同时 Add → LaserScan,并设置 Topic: /scanAn image

当前状态:

✅ 串口雷达数据
✅ Python 解析
✅ ROS2 LaserScan
✅ rviz2 显示
⬜ slam_toolbox
⬜ 建图

五、优化展示效果

目前看到的“点云”是一闪而过的,需要调整为持续显示。

  • RViz → LaserScan:
    • Decay Time = 10
      • 保留最近 5~10 秒的点,而不是一帧就消失
    • Size = 0.05
      • 或者更大,否则点太小,看不清
    • Fixed Frame = laser_frame

An image

六、相关截图

相关验证命令,验证 scan 是否有效 An image > An image