urdf 建模和 urdf_reader.cc

在一个package中新建文件夹,第一个文件夹为urdf,用来放置模型文件。第二个文件夹叫做meshes,用来放置外观纹理,一般是通过三维软件建模完成后,导出并放置在meshes中,第三个为launch文件夹。第四个是config文件夹,功能包的配置文件以及rviz的显示配置文件。

我们要准备这样的launch文件:

1
2
3
4
5
6
7
8
9
<launch>                                               
<param name="robot_description" textfile="$(find robot_description)/urdf/robot.urdf" />
<!-- 设置GUI参数,显示关节控制插件,配合下面的joint_state_publisher使用 -->
<param name="use_gui" value="true" />
<!-- 根据关节状态,创建tf关系,并发布到tf tree中 -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<!-- 发布机器人的关节状态 -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
</launch>

一个简单的模型,就是一个底盘带一个轮子:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
<?xml version="1.0" ?>
<robot name="robot">
<material name="Black">
<color rgba="0.15 0.15 0.15 1"/>
</material>
<material name="Blue">
<color rgba="0 0 0.8 1"/>
</material>

<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.5 0.3 0.01" />
</geometry>
<material name="Black"/>
</visual>
</link>

<link name="left_front_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="1.5707 0 0" />
<geometry>
<cylinder radius="0.1125" length="0.064" />
</geometry>
<material name="Blue"/>
</visual>
</link>

<joint name="left_front_joint" type="continuous">
<origin xyz="0.1375 0.182 0" rpy="0 0 0" />
<parent link="base_link" />
<child link="left_front_wheel_link" />
<axis xyz="0 1 0" />
</joint>
</robot>

有时创建URDF模型在rviz中显示时,可以显示模型形状,但不显示颜色,rviz中显示 No transform from [base_link] to [map] 。 rviz默认Fixed Frame为map,而我的模型中没有map,将Fixed Frame改为base_link,重启一遍后,模型有了颜色。 依次类推,画出另外三个轮子.

使用check_urdf robot.urdf可以检查语法,但是偶尔也有漏掉错误的时候.

第一行的xml版本声明,开头不能有空格, 也不能加注释. 在urdf文件中不能加中文注释

joint_state_publisher 和 robot_state_publisher

joint_state_publisher节点读取robot_description参数,这个就是我们的urdf文件.

use_gui参数,布尔类型,默认false,决定是否显示GUI界面. 这个小工具把所有joint做成slider形式,供用户测试,对continuous的joint,slider范围是-π到π

发布话题/joint_states, 消息类型sensor_msgs/JointState,可以echo查看

robot_state_publisher订阅话题/joint_states, tf变换也是它发布的,它有一个参数use_tf_static,用于决定是否使用tf_static latched 静态变换的广播,而这个参数默认true.
robot_state_publisher.png

一般写成launch形式:

1
2
3
4
5
6
<launch>
<param name="robot_description" textfile="$(find robot_description)/urdf/robot.urdf" />
<param name="use_gui" value="false" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
</launch>

启动launch,在rviz中加载RobotModel,如果没有map坐标系,就把全局坐标系改成base_link坐标系,会显示下面画面:
urdf.png

现在可以启动完整的机器人程序了,有了map坐标系,也就有了map->base_link转换,现在移动机器人,rviz里的模型就会跟着移动了。
机器人模型.png

问题

rviz里没有显示机器人的模型,发现终端有这样的错误:
本机rviz加载urdf出错

在urdf文件中对某个约束改名为camera,对相应的STL文件也改名后,在本地机的rviz打开RobotModel,结果终端报错:

但是rviz里没报错,tf树是正常的。最后发现还是URDF文件里的STL路径没有改过来

urdf_reader.cc

cartographer中的urdf_reader.cc是从urdf文件读取所有的坐标系变换,返回std::vector<geometry_msgs::TransformStamped>类型,然后使用下面的代码发送TF变换

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
#include "urdf_reader.h"
#include "tf2_ros/static_transform_broadcaster.h"
#include "urdf/model.h"
#include "absl/strings/str_split.h"

tf2_ros::Buffer tf_buffer;
std::vector<geometry_msgs::TransformStamped> urdf_transforms;
const std::vector<std::string> urdf_filenames =
absl::StrSplit(FLAGS_urdf_filenames, ',', absl::SkipEmpty());
for (const auto& urdf_filename : urdf_filenames) {
const auto current_urdf_transforms =
ReadStaticTransformsFromUrdf(urdf_filename, &tf_buffer);
urdf_transforms.insert(urdf_transforms.end(),
current_urdf_transforms.begin(),
current_urdf_transforms.end());
}
::tf2_ros::StaticTransformBroadcaster static_tf_broadcaster;
if (urdf_transforms.size() > 0)
static_tf_broadcaster.sendTransform(urdf_transforms);
else
ROS_WARN("no transform in urdf file !");

参考:
古月居的urdf教程
urdf文件编码导致的缺少tf变换