#改进URDF模型
在创建URDF模型中,代码显得冗长又重复,所以本期使用xacro进行改进。(本期内容是上一期内容的延续!改进完后还可以添加传感器和摄像头进行优化。)
1、创建.xacro文件
- 在xqrobot_description/urdf ⽂件夹下创建⼀个⽂件夹 xacro,并在该⽂件夹下创建xqrobot_base.xacro ⽂件
lzw08@ubuntu:~$ cd ros_ws_1/src/xqrobot_description/urdf
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf$ mkdir xacro
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf$ cd xacro/
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro$ touch xqrobot_base.xacro
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro$ gedit xqrobot_base.xacro
粘贴以下代码:
<?xml version="1.0"?>
<robot name="xqrobot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- PROPERTY LIST -->
<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"/> <!-- wheel_radius - ( base_length/2 - wheel_joint_z) -->
<xacro:property name="caster_joint_x" value="0.18"/>
<!-- Defining the colors used in this robot -->
<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>
<!-- Macro for robot wheel -->
<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>
<!-- Macro for robot caster -->
<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>
<xacro:macro name="xqrobot_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>
- 在 xqrobot_description/urdf/xacro ⽂件下创建 xqrobot.xacro ⽂件。
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro$ touch xqrobot.xacro
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro$ gedit xqrobot.xacro
粘贴以下代码:
<?xml version="1.0"?>
<robot name="xqbot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find xqrobot_description)/urdf/xacro/xqrobot_base.xacro"/>
<xqrobot_base/>
</robot>
(xqrobot.xacro文件在后面会进行填充)
2、创建display_xqrobot_xacro.launch 文件
毋庸置疑,.launch文件都是放在launch目录下的。
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro$ cd ..
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf$ cd ..
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description$ cd launch/
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/launch$ touch display_xq_xacro.launch
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/launch$ gedit display_xq_xacro.launch
粘贴以下代码:
<?xml version="1.0"?>
<launch> <arg name="model" default="$(find xacro)/xacro --inorder '$(find xqrobot_description)/urdf/xacro/xqrobot.xacro'" />
<arg name="gui" default="true" />
<param name="robot_description" command="$(arg model)" />
<!-- 设置 GUI 参数,显⽰关节控制插件 -->
<param name="use_gui" value="$(arg gui)"/>
<!-- 运⾏ joint_state_publisher 节点,发布机器⼈的关节状态 -->
<node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" />
<!-- 运⾏ robot_state_publisher 节点,发布 tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<!-- 运⾏ rviz 可视化界⾯ -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find xqrobot_description)/config/xqrobot_urdf.rviz" required="true" />
</launch>
到这里已经优化完成了,仅以上这些简短的代码,就可以实现跟上一期一样的效果了,可见.xacro即是.urdf的升级版。
3、运行,显示优化后的模型
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/launch$ cd ~/ros_ws_1
lzw08@ubuntu:~/ros_ws_1$ source devel/setup.bash
lzw08@ubuntu:~/ros_ws_1$ roslaunch xqrobot_description display_xq_xacro.launch
跟上一期一模一样的,不同点在于实现方式。
4、添加传感器和摄像头
在 xqrobot_description/urdf/xacro 路径下创建⼀个 sensor 的⽂件夹。
lzw08@ubuntu:~/ros_ws_1$ cd src/xqrobot_description/urdf/xacro/
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro$ mkdir sensors
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro$ cd sensors/
- 添加传感器
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro/sensors$ touch lidar.xacro
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro/sensors$ gedit lidar.xacro
粘贴以下代码:
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="laser">
<xacro:macro name="rplidar" params="prefix:=laser">
<link name="${prefix}_link">
<visual>
<origin xyz=" 0 0 0 " rpy="0 0 0" />
<geometry>
<cylinder length="0.06" radius="0.06"/>
</geometry>
<material name="black"/>
</visual>
</link>
</xacro:macro>
</robot>
- 添加摄像头
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro/sensors$ touch camera.xacro
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro/sensors$ gedit camera.xacro
粘贴以下代码:
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="camera">
<xacro:macro name="usb_camera" params="prefix:=camera">
<link name="${prefix}_link">
<visual>
<origin xyz=" 0 0 0 " rpy="0 0 0" />
<geometry>
<box size="0.01 0.04 0.04" />
</geometry>
<material name="black"/>
</visual>
</link>
</xacro:macro>
</robot>
5、修改路径xqrobot.xacro文件
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro/sensors$ cd ..
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro$ gedit xqrobot.xacro
更改后的xqrobot.xacro文件如下所示:
<?xml version="1.0"?>
<robot name="xqbot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find xqrobot_description)/urdf/xacro/xqrobot_base.xacro"/>
<xqrobot_base/>
<xacro:include filename="$(find xqrobot_description)/urdf/xacro/sensors/camera.xacro" />
<xacro:include filename="$(find xqrobot_description)/urdf/xacro/sensors/lidar.xacro" />
<xacro:property name="camera_offset_x" value="0.17" />
<xacro:property name="camera_offset_y" value="0" />
<xacro:property name="camera_offset_z" value="0.10" />
<xacro:property name="lidar_offset_x" value="0" />
<xacro:property name="lidar_offset_y" value="0" />
<xacro:property name="lidar_offset_z" value="0.105" />
<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>
<joint name="lidar_joint" type="fixed">
<origin xyz="${lidar_offset_x} ${lidar_offset_y} ${lidar_offset_z}" rpy="0 0 0" />
<parent link="base_link"/>
<child link="laser_link"/>
</joint>
<xacro:usb_camera prefix="camera"/>
<xacro:rplidar prefix="laser"/>
</robot>
6、运行 display_xq_xacro.launch 文件查看机器人模型
lzw08@ubuntu:~/ros_ws_1/src/xqrobot_description/urdf/xacro$ cd ~/ros_ws_1
lzw08@ubuntu:~/ros_ws_1$ roslaunch xqrobot_description display_xq_xacro.launch
7、下期见咯 ~
附本人 实践报告五(仅供参考,请勿他用)