參考視頻:【奧特學園】ROS機器人入門課程《ROS理論與實踐》零基礎教程_嗶哩嗶哩_bilibili
參考文檔:http://www.autolabor.com.cn/book/ROSTutorials/
需求描述:
使用 Xacro 優化 URDF 版的小車底盤模型實現
結果演示:

1.編寫 Xacro 文件
<!-- 使用 xacro 優化 URDF 版的小車底盤實現: 實現思路: 1.將一些常量、變量封裝為 xacro:property 比如:PI 值、小車底盤半徑、離地間距、車輪半徑、寬度 .... 2.使用 宏 封裝驅動輪以及支撐輪實現,調用相關宏生成驅動輪與支撐輪 --> <!-- 根標簽,必須聲明 xmlns:xacro --> <robot name="my_base" xmlns:xacro="http://www.ros.org/wiki/xacro"> <!-- 封裝變量、常量 --> <xacro:property name="PI" value="3.141"/> <!-- 宏:黑色設置 --> <material name="black"> <color rgba="0.0 0.0 0.0 1.0" /> </material> <!-- 底盤屬性 --> <xacro:property name="base_footprint_radius" value="0.001" /> <!-- base_footprint 半徑 --> <xacro:property name="base_link_radius" value="0.1" /> <!-- base_link 半徑 --> <xacro:property name="base_link_length" value="0.08" /> <!-- base_link 長 --> <xacro:property name="earth_space" value="0.015" /> <!-- 離地間距 --> <!-- 底盤 --> <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="green"> <color rgba="0.3 0.5 0.0 0.5" /> </material> </visual> </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> <!-- 驅動輪 --> <!-- 驅動輪屬性 --> <xacro:property name="wheel_radius" value="0.0325" /><!-- 半徑 --> <xacro:property name="wheel_length" value="0.015" /><!-- 寬度 --> <!-- 驅動輪宏實現 --> <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> </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> </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: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> </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> </xacro:macro> <xacro:add_support_wheel name="front" flag="1" /> <xacro:add_support_wheel name="back" flag="-1" /> </robot>
2.集成launch文件
方式1:先將 xacro 文件轉換出 urdf 文件,然后集成
先將 xacro 文件解析成 urdf 文件:rosrun xacro xacro xxx.xacro > xxx.urdf然后再按照之前的集成方式直接整合 launch 文件,內容示例:
<launch> <!--1.在參數服務器中載入urdf--> <param name="robot_description" textfile="$(find urdf01_rviz)/urdf/xacro/demo05_car_base.urdf" /> <!--2.啟動rviz--> <node pkg="rviz" name="rviz" type="rviz" args="-d $(find urdf01_rviz)/config/show_mycar.rviz"/> <!--3.關節狀態發布節點--> <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher"/> <!--4.機器人狀態發布節點--> <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"/> <!--5.添加控制關節運動的節點--> <node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" /> </launch>
輸入命令運行:
cys@ubuntu:~/demo05_ws$ source ./devel/setup.bash
cys@ubuntu:~/demo05_ws$ roslaunch urdf01_rviz demo06_car_base.launch

方式2:在 launch 文件中直接加載 xacro(建議使用)
launch 內容示例:
<launch> <!--1.在參數服務器中載入urdf--> <!--<param name="robot_description" textfile="$(find urdf01_rviz)/urdf/xacro/demo05_car_base.urdf" />--> <param name="robot_description" command="$(find xacro)/xacro $(find urdf01_rviz)/urdf/xacro/demo05_car_base.urdf.xacro" /> <!--2.啟動rviz--> <node pkg="rviz" name="rviz" type="rviz" args="-d $(find urdf01_rviz)/config/show_mycar.rviz"/> <!--3.關節狀態發布節點--> <node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher"/> <!--4.機器人狀態發布節點--> <node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher"/> <!--5.添加控制關節運動的節點--> <node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" /> </launch>
核心代碼:
<param name="robot_description" command="$(find xacro)/xacro $(find urdf01_rviz)/urdf/xacro/demo05_car_base.urdf.xacro" />
加載 robot_description 時使用 command 屬性,屬性值就是調用 xacro 功能包的 xacro 程序直接解析 xacro 文件。
