Xacro_完整使用流程示例

使用 Xacro 优化 URDF 版的小车底盘模型实现

1. 编写 Xacro 文件

<!--
    使用 xacro 优化 URDF 版的小车底盘实现:
    实现思路:
    1.将一些常量、变量封装为 xacro:property
      比如:PI 值、小车底盘半径、离地间距、车轮半径、宽度 ....
    2.使用 宏 封装驱动轮以及支撑轮实现,调用相关宏生成驱动轮与支撑轮
-->
<!-- 根标签,必须声明 xmlns:xacro -->

<robot name="mycar" xmlns:xacro="http://www.ros.org/wiki/xacro">
    <xacro:property name="footprint_radius" value="0.001" /> <!-- base_footprint 半径  -->

    <!-- 1.添加 base_footprint  -->
    <link name="base_footprint">
        <visual>
            <geometry>
                <sphere radius="${footprint_radius}" />
            </geometry>
        </visual>
    </link>

    <!-- 2.添加底盘 -->
<!-- 
        参数
            形状:圆柱 
            半径:10     cm 
            高度:8      cm 
            离地:1.5    cm
    -->
  <xacro:property name="base_radius" value="0.1" /> <!-- base_link 半径 -->
  <xacro:property name="base_length" value="0.08" /> <!-- base_link 长 -->
  <xacro:property name="lidi" value="0.015" /> <!-- 离地间距 -->
  <xacro:property name="base_joint_z" value="${base_length} / 2 + lidi" /> 

  <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>

  <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 m
          宽度: 0.015 m
          颜色: 黑色
      关节设置:
          x = 0
          y = 底盘的半径 + 轮胎宽度 / 2
          z = 离地间距 + 底盘长度 / 2 - 轮胎半径 = 1.5 + 4 - 3.25 = 2.25(cm)
          axis = 0 1 0
  -->
  <!-- 属性 -->
  <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">
    <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>

    <joint name="${wheel_name}2link" type="continuous">
        <parent link="base_link" />
        <child link="${wheel_name}_wheel" />
        <!-- 
            x 无偏移
            y 车体半径
            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.75 cm
          颜色: 黑色
      关节设置:
          x = 自定义(底盘半径 - 万向轮半径) = 0.1 - 0.0075 = 0.0925(cm)
          y = 0
          z = 底盘长度 / 2 + 离地间距 / 2 = 0.08 / 2 + 0.015 / 2 = 0.0475 
          axis= 1 1 1
  -->

  <xacro:property name="small_wheel_radius" value="0.0075" /> 
  <!-- Z的偏移量 = 车体高度/2 + 离地间距 - 万向轮半径 -->
  <xacro:property name="small_joint_z" value="${(base_length / 2 + lidi - small_wheel_radius) * -1 }" /> 
  <xacro:macro name = "small_wheel_func" params = "small_wheel_name flag">

    <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>

    <joint name="${small_wheel_name}2link" type="continuous">
        <parent link="base_link" />
        <child link="${small_wheel_name}_wheel" />
        <origin xyz="${0.08*flag} 0 ${small_joint_z}" rpy="0 0 0"/>
        <axis xyz="1 1 1" />
    </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文件

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

<launch>
    <!-- 1.将 urdf 文件内容设置进参数服务器 -->
    <param name="robot_description" command="$(find xacro)/xacro $(find urdf01_rviz)/urdf/xacro/demo05_car_base.urdf.xacro" />

    <!-- 2.启动 rivz -->
    <node pkg="rviz" type="rviz" name="rviz" args="-d $(find urdf01_rviz)/config/show_mycar.rviz" />

    <!-- 3.启动机器人状态和关节状态发布节点 -->
    <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" />
    <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" />

    <!-- 4.启动图形化的控制关节运动节点 -->
    <node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" />

</launch>
  • 0
    点赞
  • 2
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值