xacro完整使用列子(小车底盘实现)

需求描述:
使用 Xacro 优化 URDF 版的小车底盘模型实现

1.编写 Xacro 文件

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

    <xacro:property name="footprint_radius" value="0.001" />
    <!-- 添加base_footprint -->
    <link name="base_footprint">
        <visual>
            <geometry>
                <sphere radius="${footprint_radius}" />
            </geometry>
        </visual>
    </link>


    <!-- 2.添加底盘 -->
    <!-- 
        形状:圆柱
        半径:0,1米
        高度:0.08米
        离地距:0.015米
     -->
    <xacro:property name="base_radius" value="0.1" />
    <xacro:property name="base_length" value="0.08" />
    <xacro:property name="lidi" value="0.015" />
    <xacro:property name="base_joint_z" value="${base_length / 2 + lidi}" />
     <!-- 2.1.link -->
    <link name="base_link">
        <visual>
            <geometry>
                <cylinder radius="0.1" length="0.08" />
            </geometry>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <material name="baselink_color">
               <color rgba="1.0 0.5 0.2 0.5" /> 
            </material>
        </visual>
    </link>
    <!-- 2.2.joint -->
    <joint name="link2footprint" type="fixed">
        <parent link="base_footprint" />
        <child link="base_link" />
        <!-- 关节z上的设置=车体高度/2 + 离地间距 -->
        <origin xyz="0 0 0.055" rpy="0 0 0" />
     </joint>

     <!-- 3.添加驱动轮 -->
    <!-- 
        形状:圆柱
        半径:0.035
        长度:0.015
     -->
     <!-- 属性 -->
     <xacro:property name="wheel_radius" value="0.0325" />
     <xacro:property name="wheel_length" value="0.015" />
     <xacro:property name="PI" value="3.1415927" />
     <!-- 结果为负 -->
     <xacro:property name="wheel_joint_z" value="${(base_length / 2 + lidi - wheel_radius) * -1}" />
     <!-- 
         wheel_name: left或right
         flag:1或-1
      -->
     <xacro:macro name="wheel_func" params="wheel_name flag">
        <!-- 3.1.link -->
        <link name="${wheel_name}_wheel">
            <visual>
                <geometry>
                    <cylinder radius="${wheel_radius}" length="${wheel_length}" />
                </geometry>
                <origin xyz="0 0 0" rpy="${PI / 2} 0 0" />
                <material name="wheel_color">
                <color rgba="0 0 0 0.3" /> 
                </material>
            </visual>
        </link>

        
        <!-- 3.2.joint -->
        <joint name="${wheel_name}2link" type="continuous">
            <parent link="base_link" />
            <child link="${wheel_name}_wheel" />
            <!-- 关节z上的设置=车体高度/2 + 离地间距 -->
            <origin xyz="0 ${0.1 * flag} ${wheel_joint_z}" rpy="0 0 0" />
            <axis xyz="0 1 0" />
        </joint>
    </xacro:macro>
    <xacro:wheel_func wheel_name="left" flag="1" />
    <xacro:wheel_func wheel_name="right" flag="-1" />

    <!-- 4.添加万向轮 -->
    <!-- 
        形状:球
        半径:0.0075m
     -->
     
     <xacro:property name="small_wheel_radius" value="0.0075" />
     <xacro:property name="small_wheel_x" value="0.08" />
     <!-- z的偏移量 = 车体高度 / 2 + 离地间距 - 万向轮半径 -->
     <xacro:property name="small_wheel_z" value="${-(base_length / 2 + lidi - small_wheel_radius)}" />
     <xacro:macro name="small_wheel_func" params="small_wheel_name flag">
        <!-- 4.1.link -->
        <link name="${small_wheel_name}_wheel">
            <visual>
                <geometry>
                    <sphere radius="${small_wheel_radius}" />
                </geometry>
                <origin xyz="0 0 0" rpy="0 0 0" />
                <material name="wheel_color">
                <color rgba="0 0 0 0.3" /> 
                </material>
            </visual>
        </link>

        
        <!-- 4.2.joint -->
        <joint name="${small_wheel_name}2link" type="continuous">
            <parent link="base_link" />
            <child link="${small_wheel_name}_wheel" />
            <!-- 关节z上的设置=车体高度/2 + 离地间距 -->
            <origin xyz="${small_wheel_x * flag} 0 ${small_wheel_z}" rpy="0 0 0" />
            <axis xyz="0 1 0" />
        </joint>

     </xacro:macro>
     <xacro:small_wheel_func small_wheel_name="front" flag="1" />
     <xacro:small_wheel_func small_wheel_name="back" flag="-1" />
</robot>

2.集成launch文件

方式1:先将 xacro 文件解析成 urdf 文件:rosrun xacro xacro xxx.xacro > xxx.urdf然后再按照之前的集成方式直接整合 launch 文件,内容示例:

<launch>
    <param name="robot_description" textfile="$(find demo01_urdf_helloworld)/urdf/xacro/my_base.urdf" />

    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find demo01_urdf_helloworld)/config/helloworld.rviz" />
    <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen" />
    <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen" />
    <node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" output="screen" />

</launch>

方式2:在 launch 文件中直接加载 xacro(建议使用)

launch 内容示例:

<launch>
    <param name="robot_description" command="$(find xacro)/xacro $(find demo01_urdf_helloworld)/urdf/xacro/my_base.urdf.xacro" />

    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find demo01_urdf_helloworld)/config/helloworld.rviz" />
    <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen" />
    <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen" />
    <node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" output="screen" />

</launch>

核心代码:

<param name="robot_description" command="$(find xacro)/xacro $(find demo01_urdf_helloworld)/urdf/xacro/my_base.urdf.xacro" />

加载robot_description时使用command属性,属性值就是调用 xacro 功能包的 xacro 程序直接解析 xacro 文件。

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值