6.7.2 机器人系统仿真/URDF、Gazebo与Rviz综合运用/雷达信息仿真以及显示

6.7.2 雷达信息仿真以及显示

本节介绍的重点是,将三者结合通过gazebo模拟机器人的传感器,然后在rviz中显示这些传感器感知到的数据,主要包括:
运动控制以及里程计信息显示
雷达信息仿真以及显示
摄像头信息仿真以及显示
kinect信息仿真以及显示(带有深度信息的摄象头)

雷达仿真基本流程
1.编写一个单独的xacro文件,为机器人添加雷达配置—>雷达配置文件xacro/gazebo/laser.xacro

<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro">

    <gazebo reference="laser_link" > <!--对应之前laser的link名称-->>
        <sensor type="ray" name="rplidar" >
            <pose>0 0 0 0 0 0</pose>
            <visualize>true</visualize> <!--是否显示雷达射线-->
            <update_rate>5</update_rate> <!--刷新频率-->
            <ray>
                <scan>
                    <horizontal>
                        <samples>360</samples> <!--分辨率_射线数量-->
                        <resolution>3</resolution> <!--射线有效采样数-->
                        <min_angle>-3</min_angle> <!--平面射线角度正、负-->
                        <max_angle>3</max_angle>
                    </horizontal>
                </scan>
                <range>
                    <min>0.10</min> <!--雷达测距有效范围-->
                    <max>30.0</max>
                    <resolution>0.01</resolution>
                </range>
                <noise>
                    <!--高斯噪音,为测距仿真服务-->
                    <type>gaussian</type>
                    <mean>0.0</mean>
                    <stddev>0.01</stddev>
                </noise>
            </ray>
            <plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so" >
                <topicName>/scan</topicName> <!--节点发布的odom信息-->>
                <frameName>laser_link</frameName> <!--对应laser的link名称-->>
            </plugin>
        </sensor>
    </gazebo>
</robot>

配置文件也是从gazebo/tutorial官网中下载的,使用的是
主要要修改的是<gazebo reference="name">, <frameName>两个标签中的信息对应的都是xacro文件中laser-link的名称;而topicName是节点发布的消息,默认是/scan


2.将此文件集成进xacro总文件中—demo03_laser.launch
rviz启动文件,使用laserscan的功能,查看laser收集到环境边界信息

<launch>
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find urdf_rviz)/config/show_urdf1.rviz" />
        
    <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state" />
    <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state" />         
</launch>

3.启动gazebo,使用rviz显示雷达信息
将fixed frame设置为odom,然后add/laserscam,其topic设置为/scan
gazebo中laser射线图
rviz中显示边界散点图

  • 1
    点赞
  • 7
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值