< >
Home » Ailibot模型入门教程 » Ailibot模型入门教程-添加在gazebo使用的xacro配置文件

Ailibot模型入门教程-添加在gazebo使用的xacro配置文件

文章说明

  • 本教程主要介绍如何添加在gazebo使用的xacro配置文件
  • 通过导入的ROS模型包只有URDF模型部分,如果要在gazebo上显示,还需要进一步完善,增加相关gazebo插件和配置
  • 比如轮子的摩擦系数、雷达的模拟、相机的模拟等等
  • 本教程所提及的仿真ROS包已上传上gitee | 获取地址

文件说明

  • 在gazebo加载和使用模型除了传统的URDF设置之后,还需要添加各种不同的配置
  • 此处可以将xacro配置文件分成两部分
    • 一个部分是默认的urdf设置:ailibot_model.urdf.xacro
    • 另一部分是gazebo中的设置:ailibot_model.gazebo.xacro
  • 上述两个文件位于https://gitee.com/ncnynl/ailibot_model/tree/master/urdf

操作步骤

  • 下面来简单介绍一下这些修改的配置内容,同时也定义更规范的关节名称
  • 我们假设以后TF显示效果如下:

请输入图片描述

base_footprint与base_link
  • 本处是基于导出的URDF的base_link上再添加base_footprint的tf设定
<!-- base_footprint -->
  <link name="base_footprint"/>

<!-- d4_base -->
  <!-- base_link -->
  <link name="base_link">
    <inertial>
      <origin xyz="0 0 0.0" rpy="0 0 0" />
      <mass value="${d4_base_mass}" />
      <xacro:box_inertial mass="${d4_base_mass}" length="${d4_base_length}" width="${d4_base_width}" height="${d4_base_height}"/>
    </inertial>

    <visual>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://ailibot_model/meshes/base.STL" />
      </geometry>
      <material name="black" />
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://ailibot_model/meshes/base.STL" />
      </geometry>
    </collision>
  </link>

  <!-- base_joint -->
  <joint name="base_joint" type="fixed">
    <parent link="base_footprint"/>
    <child link="base_link"/>
    <origin xyz="0.0 0.0 0.0657" rpy="0 0 0"/>
  </joint>
Wheel 部分
  • 此处主要是简化了车轮urdf配置的代码
<!-- wheel -->
  <!-- wheel_link -->
  <xacro:macro name="wheel_link" params="prefix">
    <link name="wheel_${prefix}_link">
      <inertial>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <mass value="${wheel_mass}" />
        <xacro:cylinder_inertial mass="${wheel_mass}" radius="${wheel_diameter/2}" length="${wheel_thickness}" />
      </inertial>

      <visual>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <geometry>
          <mesh filename="package://ailibot_model/meshes//wheel_${prefix}.STL" />
        </geometry>
        <material name="light_black"/>
      </visual>

      <collision>
        <origin xyz="0 0 0" rpy="-1.57 0 0" />
        <geometry>
          <cylinder length="${wheel_thickness}" radius="${wheel_diameter/2}"/>
        </geometry>
      </collision>
    </link>
  </xacro:macro>

  <xacro:wheel_link prefix="left_front"  />
  <xacro:wheel_link prefix="right_front" />
  <xacro:wheel_link prefix="left_back"   />
  <xacro:wheel_link prefix="right_back"  />

  <!-- wheel_joint -->
  <xacro:macro name="wheel_joint" params="prefix origin_x origin_y origin_z">
    <joint name="wheel_${prefix}_joint" type="continuous">
      <origin xyz="${origin_x} ${origin_y} ${origin_z}" rpy="0 -1.57 0" />
      <parent link="base_link" />
      <child link="wheel_${prefix}_link" />
      <axis xyz="0 1 0" />
    </joint>
  </xacro:macro>

  <xacro:wheel_joint prefix="left_front"  origin_x="0.065"  origin_y="0.123"  origin_z="-0.0207" />
  <xacro:wheel_joint prefix="right_front" origin_x="0.065"  origin_y="-0.123" origin_z="-0.0207" />
  <xacro:wheel_joint prefix="left_back"   origin_x="-0.065"  origin_y="0.123" origin_z="-0.0207" />
  <xacro:wheel_joint prefix="right_back"  origin_x="-0.065" origin_y="-0.123" origin_z="-0.0207" />
laser
  • 这部分为雷达的urdf定义
<!-- laser -->
  <!-- laser_link -->
  <link name="laser">
    <inertial>
      <origin xyz="0.01057242 0.00062537 -0.01985944" rpy="0 0 0" />
      <mass value="0.248" />
      <inertia
        ixx="0.00010871"
        ixy="-0.00000112"
        ixz="-0.00003362"
        iyy="0.00020060"
        iyz="0.00000384"
        izz="0.00021945" />
    </inertial>

    <visual>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://ailibot_model/meshes/laser.STL" />
      </geometry>
      <material name="light_black"/>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://ailibot_model/meshes/laser.STL" />
      </geometry>
    </collision>
  </link>

  <!-- laser_joint -->
  <joint name="laser_joint" type="fixed">
    <origin xyz="0.0 0 0.0515" rpy="0 0 0" />
    <parent link="base_link" />
    <child link="laser" />
    <axis xyz="0 0 0" />
  </joint>
camera 部分
  • 此处主要调用realsense_ros_gazebo插件来实现d435i在gazebo的仿真
<!-- camera -->
  <xacro:realsense_d435 sensor_name="camera" parent_link="base_link" rate="10" >
    <origin xyz="0.1 0 0.005" rpy="0 0 0" />
  </xacro:realsense_d435>
imu部分的urdf定义
  • 添加imu传感器,此处可以不将imu设为一个实体
<!-- imu -->
  <link name="imu_link"/>

  <!-- imu_joint -->
  <joint name="imu_joint" type="fixed">
    <parent link="base_link"/>
    <child link="imu_link"/>
    <origin xyz="0 0 0.0" rpy="0 0 0"/>
  </joint>  
wheel_friction
  • 这部分主要为车轮在gazebo中的摩擦系数以及颜色等配置
<!-- wheel_friction -->
 <xacro:macro name="wheel_friction" params="prefix">
    <gazebo reference="wheel_${prefix}_link">
      <mu1 value="2.0"/>
      <mu2 value="1.0"/>
      <kp value="500000.0"/>
      <kd value="10.0"/>
      <minDepth>0.001</minDepth>
      <maxVel>0.1</maxVel>
      <fdir1>1 0 0</fdir1>
      <material>Gazebo/DarkGrey</material>
    </gazebo>
  </xacro:macro>

  <xacro:wheel_friction prefix="left_front"  />
  <xacro:wheel_friction prefix="right_front" />
  <xacro:wheel_friction prefix="left_back" />
  <xacro:wheel_friction prefix="right_back"  />
Gazebo中的单线雷达配置
  • 添加单线雷达配置
<!-- laser -->
  <gazebo reference="laser">
    <material>Gazebo/DarkGrey</material>
    <sensor type="ray" name="laser">
      <pose>0 0 0 0 0 3.1415</pose>
      <visualize>true</visualize>
      <update_rate>5</update_rate>
      <ray>
        <scan>
          <horizontal>
            <samples>3600</samples>
            <resolution>1</resolution>
            <min_angle>-3.14</min_angle>
            <max_angle>3.14</max_angle>
          </horizontal>
        </scan>
        <range>
          <min>0.120</min>
          <max>8</max>
          <resolution>0.015</resolution>
        </range>
        <noise>
          <type>gaussian</type>
          <mean>0.0</mean>
          <stddev>0.01</stddev>
        </noise>
      </ray>
      <plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_laser.so">
        <topicName>scan</topicName>
        <frameName>laser</frameName>
      </plugin>
    </sensor>
  </gazebo>
差分驱动插件
  • 添加gazebo中四轮小车运动所需的差分驱动插件
<!-- ros_skid_steer_drive_controller -->
  <gazebo>
    <plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
      <updateRate>10.0</updateRate>
      <robotNamespace></robotNamespace>
      <leftFrontJoint>wheel_left_front_joint</leftFrontJoint>
      <rightFrontJoint>wheel_right_front_joint</rightFrontJoint>
      <leftRearJoint>wheel_left_back_joint</leftRearJoint>
      <rightRearJoint>wheel_right_back_joint</rightRearJoint>
      <wheelSeparation>0.246</wheelSeparation>
      <wheelDiameter>0.09</wheelDiameter>
      <robotBaseFrame>base_footprint</robotBaseFrame>
      <torque>10</torque>
      <topicName>cmd_vel</topicName>
      <odometryTopic>odom</odometryTopic>
      <odometryFrame>odom</odometryFrame>
      <commandTopic>cmd_vel</commandTopic>
      <topic_name_twist>cmd_vel</topic_name_twist>
      <topic_name_odometry>odom</topic_name_odometry>
      <topic_name_joint>joint</topic_name_joint>
      <broadcastTF>true</broadcastTF>
      <covariance_x>0.0001</covariance_x>
      <covariance_y>0.0001</covariance_y>
      <covariance_yaw>0.01</covariance_yaw>
    </plugin>
  </gazebo>
imu插件
  • 添加imu插件
  <gazebo>
    <plugin name="imu_plugin" filename="libgazebo_ros_imu.so">
      <alwaysOn>true</alwaysOn>
      <bodyName>imu_link</bodyName>
      <frameName>imu_link</frameName>
      <topicName>imu/data</topicName>
      <serviceName>imu_service</serviceName>
      <gaussianNoise>0.0</gaussianNoise>
      <updateRate>0</updateRate>
      <imu>
        <noise>
          <type>gaussian</type>
          <rate>
            <mean>0.0</mean>
            <stddev>2e-4</stddev>
            <bias_mean>0.0000075</bias_mean>
            <bias_stddev>0.0000008</bias_stddev>
          </rate>
          <accel>
            <mean>0.0</mean>
            <stddev>1.7e-2</stddev>
            <bias_mean>0.1</bias_mean>
            <bias_stddev>0.001</bias_stddev>
          </accel>
        </noise>
      </imu>
    </plugin>
  </gazebo>

  <!-- base_joint -->
  <joint name="base_joint" type="fixed">
    <parent link="base_footprint"/>
    <child link="base_link"/>
    <origin xyz="0.0 0.0 0.0657" rpy="0 0 0"/>
  </joint>
Wheel 部分
  • 此处主要是简化了车轮urdf配置的代码
<!-- wheel -->
  <!-- wheel_link -->
  <xacro:macro name="wheel_link" params="prefix">
    <link name="wheel_${prefix}_link">
      <inertial>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <mass value="${wheel_mass}" />
        <xacro:cylinder_inertial mass="${wheel_mass}" radius="${wheel_diameter/2}" length="${wheel_thickness}" />
      </inertial>

      <visual>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <geometry>
          <mesh filename="package://ailibot_d4_test/meshes//wheel_${prefix}.STL" />
        </geometry>
        <material name="light_black"/>
      </visual>

      <collision>
        <origin xyz="0 0 0" rpy="-1.57 0 0" />
        <geometry>
          <cylinder length="${wheel_thickness}" radius="${wheel_diameter/2}"/>
        </geometry>
      </collision>
    </link>
  </xacro:macro>

  <xacro:wheel_link prefix="left_front"  />
  <xacro:wheel_link prefix="right_front" />
  <xacro:wheel_link prefix="left_back"   />
  <xacro:wheel_link prefix="right_back"  />

  <!-- wheel_joint -->
  <xacro:macro name="wheel_joint" params="prefix origin_x origin_y origin_z">
    <joint name="wheel_${prefix}_joint" type="continuous">
      <origin xyz="${origin_x} ${origin_y} ${origin_z}" rpy="0 -1.57 0" />
      <parent link="base_link" />
      <child link="wheel_${prefix}_link" />
      <axis xyz="0 1 0" />
    </joint>
  </xacro:macro>

  <xacro:wheel_joint prefix="left_front"  origin_x="0.065"  origin_y="0.123"  origin_z="-0.0207" />
  <xacro:wheel_joint prefix="right_front" origin_x="0.065"  origin_y="-0.123" origin_z="-0.0207" />
  <xacro:wheel_joint prefix="left_back"   origin_x="-0.065"  origin_y="0.123" origin_z="-0.0207" />
  <xacro:wheel_joint prefix="right_back"  origin_x="-0.065" origin_y="-0.123" origin_z="-0.0207" />
laser
  • 这部分为雷达的urdf定义
<!-- laser -->
  <!-- laser_link -->
  <link name="laser">
    <inertial>
      <origin xyz="0.01057242 0.00062537 -0.01985944" rpy="0 0 0" />
      <mass value="0.248" />
      <inertia
        ixx="0.00010871"
        ixy="-0.00000112"
        ixz="-0.00003362"
        iyy="0.00020060"
        iyz="0.00000384"
        izz="0.00021945" />
    </inertial>

    <visual>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://ailibot_d4_test/meshes/laser.STL" />
      </geometry>
      <material name="light_black"/>
    </visual>

    <collision>
      <origin xyz="0 0 0" rpy="0 0 0" />
      <geometry>
        <mesh filename="package://ailibot_d4_test/meshes/laser.STL" />
      </geometry>
    </collision>
  </link>

  <!-- laser_joint -->
  <joint name="laser_joint" type="fixed">
    <origin xyz="0.0 0 0.0515" rpy="0 0 0" />
    <parent link="base_link" />
    <child link="laser" />
    <axis xyz="0 0 0" />
  </joint>
camera 部分
  • 此处主要调用realsense_ros_gazebo插件来实现d435i在gazebo的仿真
<!-- camera -->
  <xacro:realsense_d435 sensor_name="camera" parent_link="base_link" rate="10" >
    <origin xyz="0.1 0 0.005" rpy="0 0 0" />
  </xacro:realsense_d435>
imu部分的urdf定义
  • 添加imu传感器,此处可以不将imu设为一个实体
<!-- imu -->
  <link name="imu_link"/>

  <!-- imu_joint -->
  <joint name="imu_joint" type="fixed">
    <parent link="base_link"/>
    <child link="imu_link"/>
    <origin xyz="0 0 0.0" rpy="0 0 0"/>
  </joint>  
wheel_friction
  • 这部分主要为车轮在gazebo中的摩擦系数以及颜色等配置
<!-- wheel_friction -->
 <xacro:macro name="wheel_friction" params="prefix">
    <gazebo reference="wheel_${prefix}_link">
      <mu1 value="2.0"/>
      <mu2 value="1.0"/>
      <kp value="500000.0"/>
      <kd value="10.0"/>
      <minDepth>0.001</minDepth>
      <maxVel>0.1</maxVel>
      <fdir1>1 0 0</fdir1>
      <material>Gazebo/DarkGrey</material>
    </gazebo>
  </xacro:macro>

  <xacro:wheel_friction prefix="left_front"  />
  <xacro:wheel_friction prefix="right_front" />
  <xacro:wheel_friction prefix="left_back" />
  <xacro:wheel_friction prefix="right_back"  />
Gazebo中的单线雷达配置
  • 添加单线雷达配置
<!-- laser -->
  <gazebo reference="laser">
    <material>Gazebo/DarkGrey</material>
    <sensor type="ray" name="laser">
      <pose>0 0 0 0 0 3.1415</pose>
      <visualize>true</visualize>
      <update_rate>5</update_rate>
      <ray>
        <scan>
          <horizontal>
            <samples>3600</samples>
            <resolution>1</resolution>
            <min_angle>-3.14</min_angle>
            <max_angle>3.14</max_angle>
          </horizontal>
        </scan>
        <range>
          <min>0.120</min>
          <max>8</max>
          <resolution>0.015</resolution>
        </range>
        <noise>
          <type>gaussian</type>
          <mean>0.0</mean>
          <stddev>0.01</stddev>
        </noise>
      </ray>
      <plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_laser.so">
        <topicName>scan</topicName>
        <frameName>laser</frameName>
      </plugin>
    </sensor>
  </gazebo>
差分驱动插件
  • 添加gazebo中四轮小车运动所需的差分驱动插件
<!-- ros_skid_steer_drive_controller -->
  <gazebo>
    <plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
      <updateRate>10.0</updateRate>
      <robotNamespace></robotNamespace>
      <leftFrontJoint>wheel_left_front_joint</leftFrontJoint>
      <rightFrontJoint>wheel_right_front_joint</rightFrontJoint>
      <leftRearJoint>wheel_left_back_joint</leftRearJoint>
      <rightRearJoint>wheel_right_back_joint</rightRearJoint>
      <wheelSeparation>0.246</wheelSeparation>
      <wheelDiameter>0.09</wheelDiameter>
      <robotBaseFrame>base_footprint</robotBaseFrame>
      <torque>10</torque>
      <topicName>cmd_vel</topicName>
      <odometryTopic>odom</odometryTopic>
      <odometryFrame>odom</odometryFrame>
      <commandTopic>cmd_vel</commandTopic>
      <topic_name_twist>cmd_vel</topic_name_twist>
      <topic_name_odometry>odom</topic_name_odometry>
      <topic_name_joint>joint</topic_name_joint>
      <broadcastTF>true</broadcastTF>
      <covariance_x>0.0001</covariance_x>
      <covariance_y>0.0001</covariance_y>
      <covariance_yaw>0.01</covariance_yaw>
    </plugin>
  </gazebo>
imu插件
  • 添加imu插件
  <gazebo>
    <plugin name="imu_plugin" filename="libgazebo_ros_imu.so">
      <alwaysOn>true</alwaysOn>
      <bodyName>imu_link</bodyName>
      <frameName>imu_link</frameName>
      <topicName>imu/data</topicName>
      <serviceName>imu_service</serviceName>
      <gaussianNoise>0.0</gaussianNoise>
      <updateRate>0</updateRate>
      <imu>
        <noise>
          <type>gaussian</type>
          <rate>
            <mean>0.0</mean>
            <stddev>2e-4</stddev>
            <bias_mean>0.0000075</bias_mean>
            <bias_stddev>0.0000008</bias_stddev>
          </rate>
          <accel>
            <mean>0.0</mean>
            <stddev>1.7e-2</stddev>
            <bias_mean>0.1</bias_mean>
            <bias_stddev>0.001</bias_stddev>
          </accel>
        </noise>
      </imu>
    </plugin>
  </gazebo>

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ailibot模型入门教程