ROS 系列学习教程(总目录)
本文目录
- 一、使用属性表示常量
- 二、使用公式
- 三、使用宏定义
- 四、include 其他文件
- 五、优化实践
对于前文介绍的 urdf 模型,我们可以使用 xacro 来优化,使其更易于维护。
优化点:
- 多次用到的尺寸用常量定义
- 计算使用公式表示,增加可读性
- 重复结构用宏定义
- 可复用的结构模块用单独文件编写,使用时在其他文件 include
一、使用属性表示常量
对于一些多次用到的常量,可以使用属性表示,以实现更好的可读性与可维护性。
<!-- 属性列表 -->
<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"/>
二、使用公式
需要计算的地方,在urdf中一般是计算好后,将结果填入用的地方,但这样就隐藏掉了计算过程,无论是可读性还是维护性都不好。
从 ROS Jade 开始,Xacro支持了 Python 表达式的解析,可以使用 Python 表达式编写计算公式,使代码复用性更强。
比如计算底盘与地面的joint,可以根据常量脚轮半径(caster_radius)与 底盘高(base_length)计算,如下:
<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>
三、使用宏定义
使用宏可以封装复杂计算、通用结构等,比如左右轮子、前后脚轮等都可以抽象为一个宏,通过不同入参生成不同对象。
<!-- 轮子宏定义 -->
<xacro:macro name="wheel" params="prefix reflect">
<joint name="${prefix}_wheel_joint" type="continuous">
<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="continuous">
<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>
四、include 其他文件
有时同一个实体可能被多个机器人使用,比如传感器,这是可以将传感器单独用一个 xacro 文件表示,然后在其他文件中 include。
比如相机,先写一个单独的相机xacro文件 camera.xacro
:
<?xml version="1.0"?>
<robot name="camera" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="usb_camera" params="prefix:=camera">
<link name="${prefix}_link">
<visual>
<origin xyz=" 0 0 0 " rpy="0 1.57 0" />
<geometry>
<cylinder radius="0.02" length="0.05" />
</geometry>
<material name="gray">
<color rgba="0.25 0.25 0.25 0.95" />
</material>
</visual>
</link>
</xacro:macro>
</robot>
然后在机器人本体的xacro文件中include这个 camera.xacro
:
<?xml version="1.0"?>
<robot name="mbot_with_camera" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find simulation_learning)/models/xacro/base.xacro" />
<xacro:include filename="$(find simulation_learning)/models/xacro/sensors/camera.xacro" />
<xacro:property name="camera_offset_x" value="0.18" />
<xacro:property name="camera_offset_y" value="0" />
<xacro:property name="camera_offset_z" value="0.055" />
<!-- 调用base宏 -->
<xacro:mbot_base />
<!-- Camera -->
<joint name="camera_joint" type="fixed">
<origin xyz="${camera_offset_x} ${camera_offset_y} ${camera_offset_z}" rpy="0 0 0" />
<parent link="base_link" />
<child link="camera_link" />
</joint>
<!-- 调用Camera宏 -->
<xacro:usb_camera prefix="camera" />
</robot>
这里注意,Xacro的 xacro:include
会把被include的文件内容解析展开到 xacro:include
的位置,所以在被include的文件中,如果有宏调用等语句,也会在 xacro:include
的地方生效。
五、优化实践
对于纯urdf实现的模型,用xacro优化后如下:
优化前,完整的urdf代码:
<?xml version="1.0"?>
<robot name="mbot">
<!-- 底盘实体描述 -->
<link name="base_link">
<visual>
<origin xyz=" 0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="0.16" radius="0.20" />
</geometry>
<material name="yellow">
<color rgba="1 0.4 0 1" />
</material>
</visual>
</link>
<!-- 左轮与底盘的关节描述 -->
<joint name="left_wheel_joint" type="continuous">
<origin xyz="0 0.19 -0.05" rpy="0 0 0" />
<parent link="base_link" />
<child link="left_wheel_link" />
<axis xyz="0 1 0" />
</joint>
<!-- 左轮实体描述 -->
<link name="left_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="1.5707 0 0" />
<geometry>
<cylinder radius="0.06" length="0.025" />
</geometry>
<material name="white">
<color rgba="1 1 1 0.9" />
</material>
</visual>
</link>
<!-- 右轮与底盘的关节描述 -->
<joint name="right_wheel_joint" type="continuous">
<origin xyz="0 -0.19 -0.05" rpy="0 0 0" />
<parent link="base_link" />
<child link="right_wheel_link" />
<axis xyz="0 1 0" />
</joint>
<!-- 右轮实体描述 -->
<link name="right_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="1.5707 0 0" />
<geometry>
<cylinder radius="0.06" length="0.025" />
</geometry>
<material name="white">
<color rgba="1 1 1 0.9" />
</material>
</visual>
</link>
<!-- 前脚轮实体描述 -->
<joint name="front_caster_joint" type="continuous">
<origin xyz="0.18 0 -0.095" rpy="0 0 0" />
<parent link="base_link" />
<child link="front_caster_link" />
<axis xyz="0 1 0" />
</joint>
<!-- 前脚轮和底盘的关节描述 -->
<link name="front_caster_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<sphere radius="0.015" />
</geometry>
<material name="black">
<color rgba="0 0 0 0.95" />
</material>
</visual>
</link>
<!-- 后脚轮实体描述 -->
<joint name="back_caster_joint" type="continuous">
<origin xyz="-0.18 0 -0.095" rpy="0 0 0" />
<parent link="base_link" />
<child link="back_caster_link" />
<axis xyz="0 1 0" />
</joint>
<!-- 后脚轮和底盘的关节描述 -->
<link name="back_caster_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<sphere radius="0.015" />
</geometry>
<material name="black">
<color rgba="0 0 0 0.95" />
</material>
</visual>
</link>
<!-- 激光雷达实体描述 -->
<link name="laser_link">
<visual>
<origin xyz=" 0 0 0 " rpy="0 0 0" />
<geometry>
<cylinder length="0.05" radius="0.05" />
</geometry>
<material name="gray">
<color rgba="0.25 0.25 0.25 0.95" />
</material>
</visual>
</link>
<!-- 激光雷达和底盘的关节描述 -->
<joint name="laser_joint" type="fixed">
<origin xyz="0 0 0.105" rpy="0 0 0" />
<parent link="base_link" />
<child link="laser_link" />
</joint>
<!-- 相机实体描述 -->
<link name="camera_link">
<visual>
<origin xyz=" 0 0 0 " rpy="0 1.57 0" />
<geometry>
<cylinder radius="0.02" length = "0.05"/>
</geometry>
<material name="gray">
<color rgba="0.25 0.25 0.25 0.95"/>
</material>
</visual>
</link>
<!-- 相机和底盘的关节描述 -->
<joint name="camera_joint" type="fixed">
<origin xyz="0.18 0 0.055" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="camera_link"/>
</joint>
</robot>
rviz中显示结果如下:
使用xacro优化后:
分成四个文件:camera.xacro
、laser.xacro
、base.xacro
和 mbot_base_with_laser_camera.xacro
camera.xacro:
<?xml version="1.0"?>
<robot name="camera" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="usb_camera" params="prefix:=camera">
<link name="${prefix}_link">
<visual>
<origin xyz="0 0 0 " rpy="0 1.57 0" />
<geometry>
<cylinder radius="0.02" length="0.05" />
</geometry>
<material name="black" />
</visual>
</link>
</xacro:macro>
</robot>
laser.xacro:
<?xml version="1.0"?>
<robot name="laser" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="laser" params="prefix:=laser">
<link name="${prefix}_link">
<visual>
<origin xyz="0 0 0 " rpy="0 0 0" />
<geometry>
<cylinder length="0.05" radius="0.05" />
</geometry>
<material name="black" />
</visual>
</link>
</xacro:macro>
</robot>
base.xacro:
<?xml version="1.0"?>
<robot name="base" 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="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.25 0.25 0.25 0.95" />
</material>
<material name="white">
<color rgba="1 1 1 0.9" />
</material>
<!-- 轮子宏定义 -->
<xacro:macro name="wheel" params="prefix reflect">
<joint name="${prefix}_wheel_joint" type="continuous">
<origin xyz="0 ${reflect*wheel_joint_y} ${wheel_radius}" 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="white" />
</visual>
</link>
</xacro:macro>
<!-- 脚轮宏定义 -->
<xacro:macro name="caster" params="prefix reflect">
<joint name="${prefix}_caster_joint" type="continuous">
<origin xyz="${reflect*caster_joint_x} 0 ${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_link">
<visual>
<origin xyz="0 0 ${2*caster_radius + base_length/2}" rpy="0 0 0" />
<geometry>
<cylinder length="${base_length}" radius="${base_radius}" />
</geometry>
<material name="yellow" />
</visual>
</link>
<!-- 调用轮子宏 -->
<xacro:wheel prefix="left" reflect="-1" />
<xacro:wheel prefix="right" reflect="1" />
<!-- 调用脚轮宏 -->
<xacro:caster prefix="front" reflect="-1" />
<xacro:caster prefix="back" reflect="1" />
</xacro:macro>
</robot>
mbot_base_with_laser_camera.xacro:
<?xml version="1.0"?>
<robot name="mbot_with_laser_camera" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find simulation_learning)/models/xacro/base.xacro" />
<xacro:include filename="$(find simulation_learning)/models/xacro/sensors/laser.xacro" />
<xacro:include filename="$(find simulation_learning)/models/xacro/sensors/camera.xacro" />
<xacro:property name="laser_offset_x" value="0" />
<xacro:property name="laser_offset_y" value="0" />
<xacro:property name="laser_offset_z" value="${2*caster_radius + base_length + laser_length/2}" />
<xacro:property name="camera_offset_x" value="0.18" />
<xacro:property name="camera_offset_y" value="0" />
<xacro:property name="camera_offset_z" value="0.165" />
<!-- 调用base宏 -->
<xacro:mbot_base />
<!-- laser_joint -->
<joint name="laser_joint" type="fixed">
<origin xyz="${laser_offset_x} ${laser_offset_y} ${laser_offset_z}" rpy="0 0 0" />
<parent link="base_link" />
<child link="laser_link" />
</joint>
<!-- 调用laser宏 -->
<xacro:laser prefix="laser" />
<!-- camera_joint -->
<joint name="camera_joint" type="fixed">
<origin xyz="${camera_offset_x} ${camera_offset_y} ${camera_offset_z}" rpy="0 0 0" />
<parent link="base_link" />
<child link="camera_link" />
</joint>
<!-- 调用Camera宏 -->
<xacro:usb_camera prefix="camera" />
</robot>
rviz中显示结果为: