URDF模型优化——xacro模型
概要
这篇文章主要讲URDF模型的进阶版——xacro模型。
有关URDF模型的建立,请参考此篇文章:
机器人仿真——URDF建模.
一、模型对比
1、URDF模型
- 模型冗长,重复内容过多;
- 参数修改麻烦,不便于二次开发;
- 没有参数计算功能
2、URDF进阶版——xacro模型
- 精简模型代码
创建宏定义
文件包含
- 提供可编程接口
常量
变量
数学计算
条件语句
二、xacro模型相关定义
1、常量
常量定义
<xacro:property name="M_PI" value="3.14159"/>
常量使用
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
2、数学计算
数学计算
<origin xyz="0 ${(motor_length+wheel_length)/2} 0" rpy="0 0 0"/>
注意:所有数学运算都会转换成浮点数进行,以保证运算精度
3、宏定义
宏定义
<xacro:macro name="name" params="A B C">
......
</xacro:macro>
宏调用
<name A="A_value" B="B_value" C="C_value" />
4、文件包含
文件包含
<xacro:include filename="$(find mbot_descripiton)/urdf/xacro/mbot_base.xacro" />
三、xacro创建小车模型
指令
cd ~/catkin_ws/src/mbot_description/urdf
mkdir xacro
cd xacro
sudo gedit mbot_base.xacro
粘贴如下内容到文本
<?xml version="1.0"?>
<robot name="mbot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926"/>
<xacro:property name="base_radius" value="0.20"/>
<xacro:property name="base_length" value="0.16"/>
<xacro:property name="wheel_radius" value="0.06"/>
<xacro:property name="wheel_length" value="0.025"/>
<xacro:property name="wheel_joint_y" value="0.19"/>
<xacro:property name="wheel_joint_z" value="0.05"/>
<xacro:property name="caster_radius" value="0.015"/>
<xacro:property name="caster_joint_x" value="0.18"/>
<material name="yellow">
<color rgba="1 0.4 0 1"/>
</material>
<material name="black">
<color rgba="0 0 0 0.95"/>
</material>
<material name="gray">
<color rgba="0.75 0.75 0.75 1"/>
</material>
<xacro:macro name="wheel" params="prefix reflect">
<joint name="${prefix}_wheel_joint" type="fixed">
<origin xyz="0 ${reflect*wheel_joint_y} ${-wheel_joint_z}" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="${prefix}_wheel_link"/>
<axis xyz="0 1 0"/>
</joint>
<link name="${prefix}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder radius="${wheel_radius}" length = "${wheel_length}"/>
</geometry>
<material name="gray" />
</visual>
</link>
</xacro:macro>
<xacro:macro name="caster" params="prefix reflect">
<joint name="${prefix}_caster_joint" type="fixed">
<origin xyz="${reflect*caster_joint_x} 0 ${-(base_length/2 + caster_radius)}" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="${prefix}_caster_link"/>
<axis xyz="0 1 0"/>
</joint>
<link name="${prefix}_caster_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="${caster_radius}" />
</geometry>
<material name="black" />
</visual>
</link>
</xacro:macro>
<xacro:macro name="mbot_base">
<link name="base_footprint">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
</link>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${base_length/2 + caster_radius*2}" rpy="0 0 0" />
<parent link="base_footprint"/>
<child link="base_link" />
</joint>
<link name="base_link">
<visual>
<origin xyz=" 0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="${base_length}" radius="${base_radius}"/>
</geometry>
<material name="yellow" />
</visual>
</link>
<wheel prefix="left" reflect="-1"/>
<wheel prefix="right" reflect="1"/>
<caster prefix="front" reflect="-1"/>
<caster prefix="back" reflect="1"/>
</xacro:macro>
</robot>
指令
sudo gedit mbot.xacro
粘贴到文本
<?xml version="1.0"?>
<robot name="arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find mbot_description)/urdf/xacro/mbot_base.xacro" />
<mbot_base/>
</robot>
指令
cd ~/catkin_ws/src/mbot_description/launch
mkdir xacro
cd xacro
sudo gedit display_mbot_base_xacro.launch
粘贴到文本
<launch>
<arg name="model" default="$(find xacro)/xacro --inorder '$(find mbot_description)/urdf/xacro/mbot.xacro'" />
<arg name="gui" default="true" />
<param name="robot_description" command="$(arg model)" />
<param name="use_gui" value="$(arg gui)"/>
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find mbot_description)/config/mbot.rviz" required="true" />
</launch>
查看演示效果
roslaunch mbot_description display_mbot_base_xacro.launch
注意修改
Fixed Frame
的map
,改为base_link
;然后点击add
添加robotmodel
。
四、总结与参考资料
1、总结
URDF模型的进阶版xacro模型,明显由于URDF模型,建模过程也简单了很多。