1、简述
统一机器人描述格式(URDF)是描述机器人模型的 XML 文件,支持Xacro(XML宏),使用Xacro来引用已经存在的XML块,创建更短且可读的XML文件。
2、初始URDF描述文件
URDF描述文件为XML格式,如下示例,定义机器人的常量。
<?xml version="1.0"?>
<robot name="sam_bot" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Define robot constants -->
<xacro:property name="base_width" value="0.31"/>
<xacro:property name="base_length" value="0.42"/>
<xacro:property name="base_height" value="0.18"/>
<xacro:property name="wheel_radius" value="0.10"/>
<xacro:property name="wheel_width" value="0.04"/>
<xacro:property name="wheel_ygap" value="0.025"/>
<xacro:property name="wheel_zoff" value="0.05"/>
<xacro:property name="wheel_xoff" value="0.12"/>
<xacro:property name="caster_xoff" value="0.14"/>
</robot>
3、示例
3.1 最终效果
使用URDF创建并在RViz中显示一个三轮小车,如下图所示:
3.2 安装依赖
sudo apt install ros-humble-joint-state-publisher-gui
sudo apt install ros-humble-xacro
3.3 创建功能包
mkdir -p nav2/src
cd nav2/src
ros2 pkg create --build-type ament_cmake sam_bot_description
3.4 编辑源码
3.4.1 编辑URDF描述文件
cd sam_bot_description/src/
mkdir description
cd description/
vi sam_bot_description.urdf
<?xml version="1.0"?>
<robot name="sam_bot" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- 定义机器人主底盘的大小和两个后轮的形状 -->
<xacro:property name="base_width" value="0.31"/> <!-- 底盘宽 -->
<xacro:property name="base_length" value="0.42"/> <!-- 底盘长 -->
<xacro:property name="base_height" value="0.18"/> <!-- 底盘高 -->
<xacro:property name="wheel_radius" value="0.10"/><!-- 后轮半径 -->
<xacro:property name="wheel_width" value="0.04"/> <!-- 后轮厚度 -->
<xacro:property name="wheel_ygap" value="0.025"/> <!-- 两轮间隙 -->
<xacro:property name="wheel_zoff" value="0.05"/> <!-- 后轮在Z轴的定位 -->
<xacro:property name="wheel_xoff" value="0.12"/> <!-- 后轮在X轴的定位 -->
<xacro:property name="caster_xoff" value="0.14"/> <!-- 前轮在X轴的定位 -->
<!-- Robot Base -->
<link name="base_link"><!-- link 表示一个完整组件,通过link来链接 -->
<visual>
<geometry><!-- 小车形状 -->
<box size="${base_length} ${base_width} ${base_height}"/>
</geometry>
<material name="Cyan"><!-- 小车颜色 -->
<color rgba="0 1.0 1.0 1.0"/>
</material>
</visual>
</link>
<!-- Robot Footprint -->
<link name="base_footprint"/> <!-- 添加一个关节base_footprint将其连接到 base_link-->
<joint name="base_joint" type="fixed">
<parent link="base_link"/>
<child link="base_footprint"/>
<origin xyz="0.0 0.0 ${-(wheel_radius+wheel_zoff)}" rpy="0 0 0"/>
</joint>
<!-- Wheels 添加两个大驱动轮 -->
<xacro:macro name="wheel" params="prefix x_reflect y_reflect">
<link name="${prefix}_link">
<visual>
<origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
</geometry>
<material name="Gray">
<color rgba="0.5 0.5 0.5 1.0"/>
</material>
</visual>
</link>
<joint name="${prefix}_joint" type="continuous">
<parent link="base_link"/>
<child link="${prefix}_link"/>
<origin xyz="${x_reflect*wheel_xoff} ${y_reflect*(base_width/2+wheel_ygap)} ${-wheel_zoff}" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
</joint>
</xacro:macro>
<xacro:wheel prefix="drivewhl_l" x_reflect="-1" y_reflect="1" />
<xacro:wheel prefix="drivewhl_r" x_reflect="-1" y_reflect="-1" />
<!-- Caster Wheel 添加前脚轮,将前脚轮建模成一个球体-->
<link name="front_caster">
<visual>
<geometry>
<sphere radius="${(wheel_radius+wheel_zoff-(base_height/2))}"/>
</geometry>
<material name="Cyan">
<color rgba="0 1.0 1.0 1.0"/>
</material>
</visual>
</link>
<joint name="caster_joint" type="fixed">
<parent link="base_link"/>
<child link="front_caster"/>
<origin xyz="${caster_xoff} 0.0 ${-(base_height/2)}" rpy="0 0 0"/>
</joint>
</robot>
3.4.2 编辑launch启动文件
cd sam_bot_description/
mkdir launch
cd launch
vi display.launch.py
import launch
from launch.substitutions import Command, LaunchConfiguration
import launch_ros
import os
def generate_launch_description():
pkg_share = launch_ros.substitutions.FindPackageShare(package='sam_bot_description').find('sam_bot_description')
default_model_path = os.path.join(pkg_share, 'src/description/sam_bot_description.urdf')
default_rviz_config_path = os.path.join(pkg_share, 'rviz/urdf_config.rviz')
robot_state_publisher_node = launch_ros.actions.Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[{'robot_description': Command(['xacro ', LaunchConfiguration('model')])}]
)
joint_state_publisher_node = launch_ros.actions.Node(
package='joint_state_publisher',
executable='joint_state_publisher',
name='joint_state_publisher',
condition=launch.conditions.UnlessCondition(LaunchConfiguration('gui'))
)
joint_state_publisher_gui_node = launch_ros.actions.Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
name='joint_state_publisher_gui',
condition=launch.conditions.IfCondition(LaunchConfiguration('gui'))
)
rviz_node = launch_ros.actions.Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', LaunchConfiguration('rvizconfig')],
)
return launch.LaunchDescription([
launch.actions.DeclareLaunchArgument(name='gui', default_value='True',
description='Flag to enable joint_state_publisher_gui'),
launch.actions.DeclareLaunchArgument(name='model', default_value=default_model_path,
description='Absolute path to robot urdf file'),
launch.actions.DeclareLaunchArgument(name='rvizconfig', default_value=default_rviz_config_path,
description='Absolute path to rviz config file'),
joint_state_publisher_node,
joint_state_publisher_gui_node,
robot_state_publisher_node,
rviz_node
])
3.4.3 编辑RViz配置文件
cd sam_bot_description/
mkdir rviz
cd rviz
vi urdf_config.rviz
Panels:
- Class: rviz_common/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /RobotModel1/Links1
- /TF1
Splitter Ratio: 0.5
Tree Height: 557
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Name: Grid
- Alpha: 0.6
Class: rviz_default_plugins/RobotModel
Description Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_description
Enabled: true
Name: RobotModel
Visual Enabled: true
- Class: rviz_default_plugins/TF
Enabled: true
Name: TF
Marker Scale: 0.3
Show Arrows: true
Show Axes: true
Show Names: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: base_link
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Name: Current View
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Saved: ~
3.5 添加编译依赖
1)修改package.xml
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>joint_state_publisher_gui</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz</exec_depend>
<exec_depend>xacro</exec_depend>
2)修改CMakeLists.txt
install(
DIRECTORY src launch rviz
DESTINATION share/${PROJECT_NAME}
)
3.6 编译
cd 功能包根目录
colcon build
. install/setup.bash
3.7 启动
ros2 launch sam_bot_description display.launch.py
3.8 效果
滑动Publisher窗口中的滑块,可以控制轮子旋转
4、URDF的官方示例
http://wiki.ros.org/urdf/Examples