简介

将机器人模型(xacro版)显示在 gazebo 中

实现流程

编写封装惯性矩阵算法的 xacro 文件

为机器人模型中的每一个 link 添加 collision 和 inertial 标签,并且重置颜色属性

在 launch 文件中启动 gazebo 并添加机器人模型

实施过程

封装惯性矩阵算法的 xacro 文件

<robot name="base" xmlns:xacro="http://wiki.ros.org/xacro">
    <!-- Macro for inertia matrix -->
    <xacro:macro name="sphere_inertial_matrix" params="m r">
        <inertial>
            <mass value="${m}" />
            <inertia ixx="${2*m*r*r/5}" ixy="0" ixz="0"
                iyy="${2*m*r*r/5}" iyz="0" 
                izz="${2*m*r*r/5}" />
        </inertial>
    </xacro:macro>

    <xacro:macro name="cylinder_inertial_matrix" params="m r h">
        <inertial>
            <mass value="${m}" />
            <inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
                iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
                izz="${m*r*r/2}" /> 
        </inertial>
    </xacro:macro>

    <xacro:macro name="Box_inertial_matrix" params="m l w h">
       <inertial>
               <mass value="${m}" />
               <inertia ixx="${m*(h*h + l*l)/12}" ixy = "0" ixz = "0"
                   iyy="${m*(w*w + l*l)/12}" iyz= "0"
                   izz="${m*(w*w + h*h)/12}" />
       </inertial>
   </xacro:macro>
</robot>

底盘 Xacro 文件

    <robot name="my_base" xmlns:xacro="http://www.ros.org/wiki/xacro">
    
        <xacro:property name="PI" value="3.1415926"/>
    
        <material name="black">
            <color rgba="0.0 0.0 0.0 1.0" />
        </material>
    
        <xacro:property name="base_footprint_radius" value="0.001" /> 
        <xacro:property name="base_link_radius" value="0.1" /> 
        <xacro:property name="base_link_length" value="0.08" /> 
        <xacro:property name="earth_space" value="0.015" /> 
        <xacro:property name="base_link_m" value="0.5" /> 
    
    
        <link name="base_footprint">
          <visual>
            <geometry>
              <sphere radius="${base_footprint_radius}" />
            </geometry>
          </visual>
        </link>
    
        <link name="base_link">
          <visual>
            <geometry>
              <cylinder radius="${base_link_radius}" length="${base_link_length}" />
            </geometry>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <material name="yellow">
              <color rgba="0.5 0.3 0.0 0.5" />
            </material>
          </visual>
          <collision>
            <geometry>
              <cylinder radius="${base_link_radius}" length="${base_link_length}" />
            </geometry>
            <origin xyz="0 0 0" rpy="0 0 0" />
          </collision>
          <xacro:cylinder_inertial_matrix m="${base_link_m}" r="${base_link_radius}" h="${base_link_length}" />
    
        </link>
    
    
        <joint name="base_link2base_footprint" type="fixed">
          <parent link="base_footprint" />
          <child link="base_link" />
          <origin xyz="0 0 ${earth_space + base_link_length / 2 }" />
        </joint>
        <gazebo reference="base_link">
            <material>Gazebo/Yellow</material>
        </gazebo>
    
     
        <xacro:property name="wheel_radius" value="0.0325" />
        <xacro:property name="wheel_length" value="0.015" />
        <xacro:property name="wheel_m" value="0.05" />
    
    
        <xacro:macro name="add_wheels" params="name flag">
          <link name="${name}_wheel">
            <visual>
              <geometry>
                <cylinder radius="${wheel_radius}" length="${wheel_length}" />
              </geometry>
              <origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" />
              <material name="black" />
            </visual>
            <collision>
              <geometry>
                <cylinder radius="${wheel_radius}" length="${wheel_length}" />
              </geometry>
              <origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" />
            </collision>
            <xacro:cylinder_inertial_matrix m="${wheel_m}" r="${wheel_radius}" h="${wheel_length}" />
    
          </link>
    
          <joint name="${name}_wheel2base_link" type="continuous">
            <parent link="base_link" />
            <child link="${name}_wheel" />
            <origin xyz="0 ${flag * base_link_radius} ${-(earth_space + base_link_length / 2 - wheel_radius) }" />
            <axis xyz="0 1 0" />
          </joint>
    
          <gazebo reference="${name}_wheel">
            <material>Gazebo/Red</material>
          </gazebo>
    
        </xacro:macro>
        <xacro:add_wheels name="left" flag="1" />
        <xacro:add_wheels name="right" flag="-1" />
    
        <xacro:property name="support_wheel_radius" value="0.0075" />
        <xacro:property name="support_wheel_m" value="0.03" />
    
     
        <xacro:macro name="add_support_wheel" params="name flag" >
          <link name="${name}_wheel">
            <visual>
                <geometry>
                    <sphere radius="${support_wheel_radius}" />
                </geometry>
                <origin xyz="0 0 0" rpy="0 0 0" />
                <material name="black" />
            </visual>
            <collision>
                <geometry>
                    <sphere radius="${support_wheel_radius}" />
                </geometry>
                <origin xyz="0 0 0" rpy="0 0 0" />
            </collision>
            <xacro:sphere_inertial_matrix m="${support_wheel_m}" r="${support_wheel_radius}" />
          </link>
    
          <joint name="${name}_wheel2base_link" type="continuous">
              <parent link="base_link" />
              <child link="${name}_wheel" />
              <origin xyz="${flag * (base_link_radius - support_wheel_radius)} 0 ${-(base_link_length / 2 + earth_space / 2)}" />
              <axis xyz="1 1 1" />
          </joint>
          <gazebo reference="${name}_wheel">
            <material>Gazebo/Red</material>
          </gazebo>
        </xacro:macro>
    
        <xacro:add_support_wheel name="front" flag="1" />
        <xacro:add_support_wheel name="back" flag="-1" />
    
    
    </robot>

> 摄像头 Xacro 文件
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
        <xacro:property  name="camera_length" value="0.01"/>
        <xacro:property  name="camera_width" value="0.025"/>
        <xacro:property  name="camera_height" value="0.025"/>
         <xacro:property  name="camera_m" value="0.001"/>
        <xacro:property  name="joint_camera_x" value="0.08"/>
        <xacro:property  name="joint_camera_y" value="0"/>
        <xacro:property  name="joint_camera_z" value="${base_link_length/2+camera_length/2}"/>

<link  name="camera">
    <visual>
            <geometry>
                    <box size="${camera_length} ${camera_width} ${camera_height} "/>
            </geometry>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <material name="black"/>
    </visual>
     <collision>
            <geometry>
                <box size="${camera_length} ${camera_width} ${camera_height}" />
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
        </collision>
        <xacro:Box_inertial_matrix m="${camera_m}" l="${camera_length}" w="${camera_width}" h="${camera_height}" />
</link>

    <gazebo reference="camera">
        <material>Gazebo/Blue</material>
    </gazebo>
<joint name="camera2baselink" type="fixed">
    <parent link="base_link"/>
    <child link="camera"/>
    <origin xyz="${joint_camera_x} ${joint_camera_y} ${joint_camera_z}"/>
</joint>

</robot>

雷达 Xacro 文件

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

        <xacro:property  name="support_length" value="0.15"/>
        <xacro:property  name="support_radius" value="0.01"/> 
         <xacro:property  name="support_m" value="0.02"/> 
        <xacro:property  name="joint_support_x" value="0.0"/>
        <xacro:property  name="joint_support_y" value="0"/>
        <xacro:property  name="joint_support_z" value="${base_link_length/2+support_length/2}"/>

        <xacro:property  name="lidar_radius" value="0.05"/>
        <xacro:property  name="lidar_length" value="0.03"/>
        <xacro:property  name="lidar_m" value="0.1"/>
        <xacro:property  name="joint_lidar_x" value="0.0"/>
        <xacro:property  name="joint_lidar_y" value="0"/>
        <xacro:property  name="joint_lidar_z" value="${lidar_length/2+support_length/2}"/>

    <link name="support">
        <visual>
                <geometry>
                    <cylinder radius="${support_radius}" length="${support_length}" />
                </geometry>
                <origin xyz="0 0 0" rpy="0 0 0"/>
                <material name="green" >
                    <color rgba="0.2 0.8 0 0.8"/>
                    </material>
            </visual>
        <collision>
            <geometry>
                <cylinder radius="${support_radius}" length="${support_length}" />
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
        </collision>
        <xacro:cylinder_inertial_matrix m="${support_m}" r="${support_radius}" h="${support_length}" />
    </link>

    <gazebo reference="support">
        <material>Gazebo/White</material>
    </gazebo>

    <joint name="support2baselink " type="fixed">
        <parent link="base_link"/>
        <child link="support"/>
        <origin xyz="${joint_support_x} ${joint_support_y} ${joint_support_z}"/>
    </joint>



    <link name="lidar">
        <visual>
            <geometry>
                <cylinder radius="${lidar_radius}" length="${lidar_length}" />
            </geometry>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <material name="red" >
                <color rgba="0.8 0.2 0 0.8"/>
                </material>
        </visual>

        <collision>
            <geometry>
                <cylinder radius="${lidar_radius}" length="${lidar_length}" />
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
        </collision>
        <xacro:cylinder_inertial_matrix m="${lidar_m}" r="${lidar_radius}" h="${lidar_length}" />

    </link>

        <gazebo reference="lidar">
        <material>Gazebo/Black</material>
        </gazebo>

    <joint name="lidar2baselink" type="fixed">
        <parent link="support"/>
        <child link="lidar"/>
        <origin xyz="${joint_lidar_x} ${joint_lidar_y} ${joint_lidar_z}"/>
    </joint>

</robot>

组合Xacro 文件

<!-- 组合小车底盘与摄像头 -->
<robot name="my_car_camera" xmlns:xacro="http://wiki.ros.org/xacro">
        <!--惯性封装文件-->
        <xacro:include filename="my_head.urdf.xacro" />
        <!--小车组件文件-->
        <xacro:include filename="urdf_demo01_carbase.urdf.xacro"/>
        <xacro:include filename="urdf_demo01_camera.urdf.xacro"/>
        <xacro:include filename="urdf_demo01_lidar.urdf.xacro"/>
</robot>

launch 文件

<launch>
    <!-- 将 Urdf 文件的内容加载到参数服务器 -->
    <param name="robot_description" command="$(find xacro)/xacro $(find urdf_gazebo_demo)/urdf/urdf/car.urdf.xacro" />

    <!-- 启动 gazebo -->
    <include file="$(find gazebo_ros)/launch/empty_world.launch" />

    <!-- 在 gazebo 中显示机器人模型 -->
    <node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model mycar -param robot_description"  />
</launch>

最终现象

请输入图片描述 请输入图片描述

最后修改:2023 年 11 月 10 日
如果觉得我的文章对你有用,请随意赞赏