激光雷达

原理

激光雷达(LiDAR) 是一种利用激光进行距离测量和环境感知的传感器。它通过发射激光束并接收反射光来测量物体的距离,生成点云数据,用于构建环境的三维模型。激光雷达在机器人、自动驾驶、无人机等领域有广泛应用。

RViz 是 ROS(Robot Operating System)中的一个可视化工具,用于显示和调试机器人数据。它支持多种数据类型,包括机器人模型、传感器数据、点云、图像等。

Gazebo 是一个物理仿真器,用于模拟机器人在虚拟环境中的行为。它支持多种机器人模型和传感器,并提供物理仿真功能。

roslaunch wpr_simulation  wpb_simple.launch
 roslaunch wpr_simulation wpb_rviz.launch

在这里插入图片描述

消息包格式

雷达信息消息包https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/LaserScan.html
https://docs.ros.org/en/noetic/api/sensor_msgs/html/

rostopic echo /scan --noarr 是一个 ROS(Robot Operating System)命令,用于订阅并显示 /scan 话题上的消息内容。–noarr 参数用于简化输出,不显示数组的完整内容,而是显示数组的类型和长度。

llk@LLK:~$ rostopic echo /scan --noarr
header:
  seq: 14445
  stamp:
    secs: 1533
    nsecs: 920000000
  frame_id: "laser"
angle_min: -3.141590118408203
angle_max: 3.141590118408203
angle_increment: 0.017501894384622574
time_increment: 0.0
scan_time: 0.0
range_min: 0.23999999463558197
range_max: 6.0
ranges: "<array type: float32, length: 360>"
intensities: "<array type: float32, length: 360>"
---
  1. header
    seq: 消息的序列号,用于标识消息的顺序。在这个例子中,seq: 14445 表示这是第 14445 条消息。
    stamp: 消息的时间戳,表示消息的生成时间。
    secs: 时间戳的秒部分,secs: 1533 表示消息生成于 1533 秒。
    nsecs: 时间戳的纳秒部分,nsecs: 920000000 表示消息生成于 920,000,000 纳秒。
    frame_id: 消息的参考坐标系,frame_id: “laser” 表示消息的参考坐标系是 laser。
  2. angle_min 和 angle_max
    angle_min: 扫描的起始角度,单位为弧度。angle_min: -3.141590118408203 表示扫描从 -π 弧度(即 -180 度)开始。
    angle_max: 扫描的结束角度,单位为弧度。angle_max: 3.141590118408203 表示扫描到 π 弧度(即 180 度)结束。
  3. angle_increment
    angle_increment: 扫描的角度增量,单位为弧度。angle_increment: 0.017501894384622574 表示每个扫描点之间的角度增量约为 1 度(0.0175 弧度)。
  4. time_increment 和 scan_time
    time_increment: 扫描中相邻两个测量之间的时间增量,单位为秒。time_increment: 0.0 表示相邻两个测量之间的时间增量为 0 秒,通常用于静态扫描。
    scan_time: 完成一次完整扫描所需的时间,单位为秒。scan_time: 0.0 表示扫描时间为 0 秒,通常用于静态扫描。
  5. range_min 和 range_max
    range_min: 激光雷达可以可靠测量的最小距离,单位为米。range_min: 0.23999999463558197 表示最小测量距离为 0.24 米。
    range_max: 激光雷达可以可靠测量的最大距离,单位为米。range_max: 6.0 表示最大测量距离为 6 米。
  6. ranges 和 intensities
    ranges: 一个浮点数数组,包含从激光雷达到各个障碍物的距离。ranges: “<array type: float32, length: 360>” 表示数组中有 360 个浮点数,每个浮点数表示一个特定角度的距离。
    intensities: 一个浮点数数组,包含与 ranges 数组中的距离对应的反射强度值。intensities: “<array type: float32, length: 360>” 表示数组中有 360 个浮点数,每个浮点数表示一个特定角度的反射强度。

获取激光雷达数据

 roslaunch  wpr_simulation  wpb_simple.launch
 rosrun wpr_simulation   demo_lidar_data

在这里插入图片描述

在这里插入图片描述
在这里插入图片描述

catkin_create_pkg lidar_pkg roscpp rospy sensor_msgs

激光雷达避障

当接收到雷达信息后,判断是否有障碍物进行转动

在这里插入图片描述
当没有接收到新的速度数据包时,会按照原来的数据包规定的速度来运动

#include <ros/ros.h>
#include <sensor_msgs/LaserScan.h>
#include <geometry_msgs/Twist.h>
// geometry_msgs 是 ROS 中的一个标准消息包,它定义了几何相关的消息类型,如 Point、Vector3、Twist 等。
// sensor_msgs 包依赖于 geometry_msgs,因此当你在 find_package 中指定了 sensor_msgs 时,catkin 会自动加载 geometry_msgs 作为依赖项。
ros::Publisher vel_pub;
static int nCount=0;
void LidarCallback(const sensor_msgs::LaserScan msg)
{   
    //fmiddist 通常是指 前方中间距离(Front Middle Distance)的缩写。它表示激光雷达在正前方方向(通常是 180 度)测得的距离值
    float FMidDist=msg.ranges[180];
    ROS_INFO("前方测距 ranges[180] = %f 米", FMidDist);
    //避障部分
    if(nCount>0)
    {
        nCount--;
        return;  //继续保持之前的运动
    }
    geometry_msgs::Twist twist;
    if(FMidDist<1.5) //1.5米 一个grid是1米
    {
        twist.angular.z = 0.5;
        nCount=30;
    }
    else
    {
        twist.linear.x = 0.5;  
    }
    vel_pub.publish(twist);
}

int main(int argc, char *argv[])
{
    setlocale(LC_ALL,"");
    ros::init(argc,argv,"lidar_node");
    ros::NodeHandle n;
    ros::Subscriber lidar_sub = n.subscribe("/scan",10,&LidarCallback);
    //避障部分
    vel_pub = n.advertise<geometry_msgs::Twist>("/cmd_vel",10);
    //得到scan话题里的雷达数据后选择行为
    ros::spin();
    return 0;
}
#! /usr/bin/env python3
#coding=utf-8

import rospy
from sensor_msgs.msg import LaserScan
from geometry_msgs.msg import Twist
count=0
def LidarCallback(msg):
    global vel_pub
    global count
    FMidDist=msg.ranges[180]
    rospy.loginfo("前方测距 ranges[180] = %.2f 米",FMidDist)
    if count>0:
        count=count-1
        return
    vel_cmd=Twist()
    if FMidDist<1.5:
        vel_cmd.angular.z=0.5
        count=30
    else:
        vel_cmd.linear.x=0.5
    vel_pub.publish(vel_cmd)

if __name__=="__main__":
    rospy.init_node("lidar_node")
    lidar_sub=rospy.Subscriber("/scan",LaserScan,LidarCallback,queue_size=10)
    vel_pub=rospy.Publisher("/cmd_vel",Twist,queue_size=10)
    rospy.spin()
 
Logo

火山引擎开发者社区是火山引擎打造的AI技术生态平台,聚焦Agent与大模型开发,提供豆包系列模型(图像/视频/视觉)、智能分析与会话工具,并配套评测集、动手实验室及行业案例库。社区通过技术沙龙、挑战赛等活动促进开发者成长,新用户可领50万Tokens权益,助力构建智能应用。

更多推荐