gazebo 添加16线velodyne激光雷达 详细教程

gazebo 添加16线velodyne激光雷达 详细教程

步骤:

  1. 找到velodyne的文件
  2. 修改相关的xacro文件
  3. 调用文件
  4. 让机器人带着雷达跑起来,查看效果

1、找到velodyne的文件:
这一步许多文章都没有提到。还要自己新建一个xacro文件。实际可以在这里直接下载:https://bitbucket.org/DataspeedInc/velodyne_simulator/src/master/velodyne_description/
(鸣谢@大神yjn
下载后可以看到文件夹:velodyne_simulator,其中有:
gazebo 添加16线velodyne激光雷达 详细教程

将【velodyne_description】拷贝到src中。

gazebo 添加16线velodyne激光雷达 详细教程
文件夹【urdf】中的VLP-16.URDF.xacro就是16线雷达的模型文件

2、修改VLP-16.URDF.xacro
在实际调用文件夹的过程中,发现会提示“Not enough blocks”
gazebo 添加16线velodyne激光雷达 详细教程
所以要对VLP-16.URDF.xacro进行修改:
1、把*origin删掉,不然与<xacro:insert_block name=“origin” /> 一起,会造成报错:“Not enough blocks”。
2、把joint删掉,在总xacro文件中声明joint即可,不用重复声明。
3、把parent:=base_link改为自己的机器人link名字,不然又报错。
gazebo 添加16线velodyne激光雷达 详细教程
3、在总的xacro文件中,调用这个16线雷达的xacro文件

<?xml version="1.0"?>
<robot name="arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
    <xacro:include filename="$(find top_mbot)/urdf/xacro/gazebo/robot_base_gazebo.xacro"/>             # 声明机器人的xacro文件位置
    <xacro:include filename="$(find top_mbot)/urdf/xacro/sensor/16_lidar_gazebo.xacro"/>                     # 声明16线雷达的xacro文件位置

    <!-- lidar -->
    <joint name="lidar_joint" type="fixed">                                                                                                                          #设置joint,注意z的值,设为机器人的高度
        <origin xyz="0 0 0.1" rpy="0 0 0" />
        <parent link="base_robot_link"/>
        <child link="velodyne_base_link"/>
    </joint>
    
    <xacro:VLP-16/>                                                                                                                                                                            # 调用16线雷达的宏文件
    <robot_base_gazebo/>                                                                                                                                                             # 调用机器人本体的宏文件

</robot>

4、让机器人跑起来,查看效果
注意啊,要让机器人跑起来,launch文件中要首先打开arbotix节点,让机器人能按照指令跑起来

    <!--打开artrix差速器驱动节点-->
    <node name="arbotix" pkg="arbotix_python" type="arbotix_driver" output="screen">
        <rosparam file="$(find top_mbot)/config/fake_mbot_arbotix.yaml" command="load" />
        <param name="sim" value="true"/>
    </node>

而且要根据机器人的具体尺寸,修改fake_mbot_arbotix.yaml文件,包括坐标系(base_frame_id)、轮距( base_width)

controllers: {
   base_controller: {
       type: diff_controller, 
       base_frame_id: base_robot_link,
       base_width: 0.2,
       ticks_meter: 4100, 
       Kp: 12, 
       Kd: 12, 
       Ki: 0, 
       Ko: 50, 
       accel_limit: 1.0 
    }
}

最后还要适当加大机器人本体的质量,将box_mass由2提高到20,不然跑起来晃动很厉害

    <xacro:property name="box_mass" value="20"/>

最后,发布运动的指令,让机器人圆周运动(线速度0.5,角速度-3):

rostopic pub /cmd_vel    geometry_msgs/Twist -r 24 -- '[0.5, 0.0, 0.0]' '[0.0, 0.0, -3]'

这样,终于跑起来了:
gazebo 添加16线velodyne激光雷达 详细教程
gazebo 添加16线velodyne激光雷达 详细教程
真是麻烦死了,从入门到放弃。
下班

上一篇:Unsupervised Deep Image Stitching代码理解


下一篇:ROS仿真笔记之——gazebo配置velodyne