时隔半个月继续整毕设的ROS部分,中间在做路径规划算法matlab仿真的部分。不知道还能不能毕业。
我接下来的笔记多来源于:
Introduction · Autolabor-ROS机器人入门课程《ROS理论与实践》零基础教程
这位老师讲解的非常棒。我的笔记增加的内容主要是视频中一些具体示例的操作和代码,以及一些报错的解决,还有视频中提到,但教程中没有写出来的知识。原创是不可能原创的。
URDF文件的缺点:
1.URDF依赖人工计算,参数改变需要重新计算。
2.URDF代码存在高度重复,没有考虑封装。
Xacro的优势:
1.能实现代码复用。
2.Xacro变量方便参数设计。
一、建立Xacro文件并且转换成URDF文件
首先演示一下如何将Xacro文件转换成urdf文件。
首先,在/DEMO05_WS/src/urdf01_rviz/urdf/xacro目录下建立Xacro文件,文件名为demo01_helloworld.urdf.xacro,内容如下:
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- 属性封装 -->
<xacro:property name="wheel_radius" value="0.0325" />
<xacro:property name="wheel_length" value="0.0015" />
<xacro:property name="PI" value="3.1415927" />
<xacro:property name="base_link_length" value="0.08" />
<xacro:property name="lidi_space" value="0.015" />
<!-- 宏 -->
<xacro:macro name="wheel_func" params="wheel_name flag" >
<link name="${wheel_name}_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
</geometry>
<origin xyz="0 0 0" rpy="${PI / 2} 0 0" />
<material name="wheel_color">
<color rgba="0 0 0 0.3" />
</material>
</visual>
</link>
<!-- 3-2.joint -->
<joint name="${wheel_name}2link" type="continuous">
<parent link="base_link" />
<child link="${wheel_name}_wheel" />
<!--
x 无偏移
y 车体半径
z z= 车体高度 / 2 + 离地间距 - 车轮半径
-->
<origin xyz="0 ${0.1 * flag} ${(base_link_length / 2 + lidi_space - wheel_radius) * -1}" rpy="0 0 0" />
<axis xyz="0 1 0" />
</joint>
</xacro:macro>
<xacro:wheel_func wheel_name="left" flag="1" />
<xacro:wheel_func wheel_name="right" flag="-1" />
</robot>
再将Xacro文件转换成URDF文件:命令行进入 xacro文件 所属目录,执行:rosrun xacro xacro xxx.xacro > xxx.urdf
milk@milk:~/DEMO05_WS/src/urdf01_rviz/urdf/xacro$ rosrun xacro xacro demo01_helloworld.urdf.xacro >demo01_helloworld.urdf
执行以上操作后,xacro 文件解析为 名为demo01_helloworld.urdf的urdf 文件,内容如下:
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from test.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="mycar">
<link name="left_wheel">
<visual>
<geometry>
<cylinder length="0.0015" radius="0.0325"/>
</geometry>
<origin rpy="1.57079635 0 0" xyz="0 0 0"/>
<material name="wheel_color">
<color rgba="0 0 0 0.3"/>
</material>
</visual>
</link>
<!-- 3-2.joint -->
<joint name="left2link" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<!--
x 无偏移
y 车体半径
z z= 车体高度 / 2 + 离地间距 - 车轮半径
-->
<origin rpy="0 0 0" xyz="0 0.1 -0.0225"/>
<axis xyz="0 1 0"/>
</joint>
<link name="right_wheel">
<visual>
<geometry>
<cylinder length="0.0015" radius="0.0325"/>
</geometry>
<origin rpy="1.57079635 0 0" xyz="0 0 0"/>
<material name="wheel_color">
<color rgba="0 0 0 0.3"/>
</material>
</visual>
</link>
<!-- 3-2.joint -->
<joint name="right2link" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<!--
x 无偏移
y 车体半径
z z= 车体高度 / 2 + 离地间距 - 车轮半径
-->
<origin rpy="0 0 0" xyz="0 -0.1 -0.0225"/>
<axis xyz="0 1 0"/>
</joint>
</robot>
PS:在执行以上操作之前,先在另一个新终端输入roscore
二、Xacro语法
这里学习如何封装变量并使用算术运算,以及Xacro语法中的宏和文件包含
1.属性与算数运算
属性用于封装 URDF 中的一些字段,比如: PAI 值,小车的尺寸,轮子半径 ....
举例:在/DEMO05_WS/src/urdf01_rviz/urdf/xacro目录下新建:demo02_field.urdf.xacro
在这个文件里进行属性定义、属性调用、算术运算。
(1)属性定义
<robot name = "maycar" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- 1.属性定义-->
<xacro:property name = "PI" value = "3.1415927">
<xacro:property name = "radius" value = "0.03">
<!-- 2.属性调用 -->
<!-- 3.算术运算 -->
</robot>
定义pai : 属性名称:PI ;属性值:3.1415927
定义车轮半径: 属性名称:radius; 属性值:0.03
(2)属性调用
调用方式:
${属性名称}
示例:自定义标签 myUsePropertyxxx ,调用PI和radius
<robot name = "maycar" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- 1.属性定义-->
<xacro:property name = "PI" value = "3.1415927" />
<xacro:property name = "radius" value = "0.03" />
<!-- 2.属性调用 -->
<myUsePropertyxxx name="${PI}" />
<myUsePropertyxxx name="${radius}" />
<!-- 3.算术运算 -->
</robot>
执行一下当前文件以输出结果:
milk@milk:~/DEMO05_WS/src/urdf01_rviz/urdf/xacro$ rosrun xacro xacro demo02_field.urdf.xacro
输出结果:
<?xml version="1.0" encoding="utf-8"?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from demo02_field.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="mycar">
<!-- 2.属性调用 -->
<myUsePropertyxxx name="3.1415927"/>
<myUsePropertyxxx name="0.03"/>
<!-- 3.算术运算 -->
</robot>
在这一步我出现了一个运行错误:
milk@milk:~/DEMO05_WS/src/urdf01_rviz/urdf/xacro$ rosrun xacro xacro demo02_field.urdf.xacro
XML parsing error: no element found: line 1, column 0
when processing file: demo02_field.urdf.xacro
Check that:
- Your XML is well-formed
- You have the xacro xmlns declaration: xmlns:xacro="http://www.ros.org/wiki/xacro"
原来在执行rosrun之前,要先把这个文件保存一下……
(3)算术运算
对刚才定义的参数进行加减乘除取余等算术运算操作,实现方式:
${数学表达式}
编写数学表达式,实现以下功能:将PI除以2,radius乘2:
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- 1.属性定义-->
<xacro:property name = "PI" value = "3.1415927" />
<xacro:property name = "radius" value = "0.03" />
<!-- 2.属性调用 -->
<myUsePropertyxxx name="${PI}" />
<myUsePropertyxxx name="${radius}" />
<!-- 3.算术运算 -->
<myUsePropertyYyy result="${PI / 2}" />
<myUsePropertyYyy result="${radius * 2}" />
</robot>
执行(步骤同上)结果:
<robot name="mycar">
<!-- 2.属性调用 -->
<myUsePropertyxxx name="3.1415927"/>
<myUsePropertyxxx name="0.03"/>
<!-- 3.算术运算 -->
<myUsePropertyYyy result="1.57079635"/>
<myUsePropertyYyy result="0.06"/>
</robot>
2.宏
宏类似于函数实现,作用是:提高代码复用率,优化代码结构,提高安全性。
(1)宏定义
<xacro:macro name="宏名称" params="参数列表(多参数之间使用空格分隔)">
.....
参数调用格式: ${参数名}
</xacro:macro>
(2)宏调用
<xacro:宏名称 参数1=xxx 参数2=xxx/>
(3)举例
在/DEMO05_WS/src/urdf01_rviz/urdf/xacro目录下新建:demo03_macro.urdf.xacro,用于演示宏的定义和调用
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- 1.宏定义-->
<xacro:macro name = "getSum" params= "num1 num2" >
<result value = "${num1 + num2}" />
</xacro:macro >
<!-- 2.宏调用-->
<xacro:getSum num1= " 1" num2 = "5" />
</robot>
rosrun执行以上代码,实现将num1和num2相加。
milk@milk:~/DEMO05_WS/src/urdf01_rviz/urdf/xacro$ rosrun xacro xacro demo03_macro.urdf.xacro
执行结果:
<robot name="mycar">
<result value="6"/>
</robot>
3.文件包含
机器人由多部件组成,不同部件可以封装为单独的 xacro 文件,最后再将不同的文件集成,组合为完整机器人的机器人模型,可以使用文件包含实现。
(1)文件包含的语法:
<robot name="xxx" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="my_base.xacro" />
<xacro:include filename="my_camera.xacro" />
<xacro:include filename="my_laser.xacro" />
....
</robot>
filename的值是被包含的文件。
(2)案例
要求:创建一个新的文件,在此文件中包含之前写过的demo02和demo03
实现:
首先,在/DEMO05_WS/src/urdf01_rviz/urdf/xacro目录下新建:demo04_sum.urdf.xacro
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- 1.演示文件包含-->
<xacro:include filename="demo02_field.urdf.xacro" />
<xacro:include filename="demo03_macro.urdf.xacro" />
</robot>
执行。
milk@milk:~/DEMO05_WS/src/urdf01_rviz/urdf/xacro$ rosrun xacro xacro demo04_sum.urdf.xacro
结果:
<robot name="mycar">
<!-- 2.属性调用 -->
<myUsePropertyxxx name="3.1415927"/>
<myUsePropertyxxx name="0.03"/>
<!-- 3.算术运算 -->
<myUsePropertyYyy result="1.57079635"/>
<myUsePropertyYyy result="0.06"/>
<result value="6"/>
</robot>
输出了demo02和demo03的结果。
三、Xacro的完整使用
需求:使用 Xacro 优化 URDF 版的小车底盘模型实现。
1.编写Xacro文件
首先,在/DEMO05_WS/src/urdf01_rviz/urdf/xacro目录下新建:demo05_car_base.urdf.xacro
<!--
使用 xacro 优化 URDF 版的小车底盘实现:
实现思路:
1.将一些常量、变量封装为 xacro:property
比如:PI 值、小车底盘半径、离地间距、车轮半径、宽度 ....
2.使用 宏 封装驱动轮以及支撑轮实现,调用相关宏生成驱动轮与支撑轮
-->
<!-- 根标签,必须声明 xmlns:xacro -->
<robot name="my_base" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- 封装变量、常量 -->
<xacro:property name="PI" value="3.141"/>
<!-- 宏:黑色设置 -->
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
<!-- 底盘属性 -->
<xacro:property name="base_footprint_radius" value="0.001" /> <!-- base_footprint 半径 -->
<xacro:property name="base_link_radius" value="0.1" /> <!-- base_link 半径 -->
<xacro:property name="base_link_length" value="0.08" /> <!-- base_link 长 -->
<xacro:property name="earth_space" value="0.015" /> <!-- 离地间距 -->
<!-- 底盘 -->
<link name="base_footprint">
<visual>
<geometry>
<sphere radius="${base_footprint_radius}" />
</geometry>
</visual>
</link>
<link name="base_link">
<visual>
<geometry>
<cylinder radius="${base_link_radius}" length="${base_link_length}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="yellow">
<color rgba="0.5 0.3 0.0 0.5" />
</material>
</visual>
</link>
<joint name="base_link2base_footprint" type="fixed">
<parent link="base_footprint" />
<child link="base_link" />
<origin xyz="0 0 ${earth_space + base_link_length / 2 }" />
</joint>
<!-- 驱动轮 -->
<!-- 驱动轮属性 -->
<xacro:property name="wheel_radius" value="0.0325" /><!-- 半径 -->
<xacro:property name="wheel_length" value="0.015" /><!-- 宽度 -->
<!-- 驱动轮宏实现 -->
<xacro:macro name="add_wheels" params="name flag">
<link name="${name}_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" />
<material name="black" />
</visual>
</link>
<joint name="${name}_wheel2base_link" type="continuous">
<parent link="base_link" />
<child link="${name}_wheel" />
<origin xyz="0 ${flag * base_link_radius} ${-(earth_space + base_link_length / 2 - wheel_radius) }" />
<axis xyz="0 1 0" />
</joint>
</xacro:macro>
<xacro:add_wheels name="left" flag="1" />
<xacro:add_wheels name="right" flag="-1" />
<!-- 支撑轮 -->
<!-- 支撑轮属性 -->
<xacro:property name="support_wheel_radius" value="0.0075" /> <!-- 支撑轮半径 -->
<!-- 支撑轮宏 -->
<xacro:macro name="add_support_wheel" params="name flag" >
<link name="${name}_wheel">
<visual>
<geometry>
<sphere radius="${support_wheel_radius}" />
</geometry>
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="black" />
</visual>
</link>
<joint name="${name}_wheel2base_link" type="continuous">
<parent link="base_link" />
<child link="${name}_wheel" />
<origin xyz="${flag * (base_link_radius - support_wheel_radius)} 0 ${-(base_link_length / 2 + earth_space / 2)}" />
<axis xyz="1 1 1" />
</joint>
</xacro:macro>
<xacro:add_support_wheel name="front" flag="1" />
<xacro:add_support_wheel name="back" flag="-1" />
</robot>
xacro文件写入urdf:
milk@milk:~/DEMO05_WS/src/urdf01_rviz/urdf/xacro$ rosrun xacro xacro demo05_car_base.urdf.xacro > demo05_car_base.urdf
这样在xacro目录下多了一个demo05_car_base.urdf
注意,这里要把demo05_car_base.urdf中的中文注释删掉,否则在后面启动rivz的时候会报错。
2.集成launch文件
集成launch文件有两种方法:
(1)将xacro文件转化成urdf文件后集成
先将 xacro 文件解析成 urdf 文件:rosrun xacro xacro xxx.xacro > xxx.urdf
然后再按照之前的集成方式直接整合 launch 文件。
具体实现:
首先,在/DEMO05_WS/src/urdf01_rviz/urdf/xacro目录下新建:demo06_car_base.launch
内容:
<launch>
<!-- 1.在参数服务器中载入urdf-->
<param name="robot_description" textfile="$(find demo01_urdf_helloworld)/urdf/xacro/demo05_car_base.urdf" />
<!-- 2.启动rviz-->
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find demo01_urdf_helloworld)/config/helloworld.rviz" />
<!-- 3.添加关节状态发布节点-->
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen" />
<!-- 4.添加机器人状态发布节点-->
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen" />
<!-- 5.添加关节运动控制节点-->
<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" output="screen" />
</launch>
执行:
首先进入当前工作空间进行source
milk@milk:~/DEMO05_WS$ source ./devel/setup.bash
(ps:这一步我一开始出现错误:
bash: ./devel/setup/bash: 没有那个文件或目录
我的解决办法:回到工作空间下重新编译:
catkin_make
这样再source就没有错误了。)
roslaunch:
milk@milk:~/DEMO05_WS$ roslaunch urdf01_rviz demo06_car_base.launch
rivz启动,启动后是没有模型的,需要增加模型,点左边的add,选择RobotModel如图
并且,将Fixed Frame的map改为base_footprint,这样就可以看到小车模型。
(2)在 launch 文件中直接加载 xacro(建议使用)
这种方法不需要生成中间文件.urdf,直接集成xacro
将demo06_car_base.launch修改一下,文件内容:
<launch>
<param name="robot_description" command="$(find xacro)/xacro $(find urdf01_rviz)/urdf/xacro/demo05_car_base.urdf.xacro" />
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find urdf01_rviz)/config/show_mycar.rviz" />
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen" />
<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" output="screen" />
</launch>
这样,我们不需要生成对应的urdf文件,直接进行roslaunch:
milk@milk:~/DEMO05_WS$ roslaunch urdf01_rviz demo06_car_base.launch
rviz启动。
四、Xacro添加部件
需求:在前面小车底盘基础之上,添加摄像头和雷达传感器。
实现分析:机器人模型由多部件组成,可以将不同组件设置进单独文件,最终通过文件包含实现组件的拼装。
实现流程:
-
首先编写摄像头和雷达的 xacro 文件
-
然后再编写一个组合文件,组合底盘、摄像头与雷达
-
最后,通过 launch 文件启动 Rviz 并显示模型
我们需要建立以及几个文件:1.摄像头文件demo06_car_camera.urdf.xacro雷达文件demo07_car_laser.urdf.xacro。2.用于汇总小车底盘、摄像头和雷达的文件car.urdf.xacro。3.用于集成的launch文件car.launch。
1.组合底盘摄像头与雷达的 xacro 文件
用于汇总小车底盘、摄像头和雷达的文件car.urdf.xacro
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="demo05_car_base.urdf.xacro" />
<xacro:include filename="demo06_car_camera.urdf.xacro" />
<xacro:include filename="demo07_car_laser.urdf.xacro" />
</robot>
2.launch 文件
和之前的launch文件类似,car.launch的内容如下:
<launch>
<param name="robot_description" command="$(find xacro)/xacro $(find urdf01_rviz)/urdf/xacro/car.urdf.xacro" />
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find urdf01_rviz)/config/show_mycar.rviz" />
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" output="screen" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen" />
<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="joint_state_publisher_gui" output="screen" />
</launch>
3.摄像头和雷达 Xacro 文件实现
(1)摄像头
关于摄像头,我们需要设置的有摄像头的参数,以及连杆和关节。
上图的摄像头(小车前方黑色小方块)是一个立方体,需要考虑:立方体的宽度、高度、厚度。
摄像头的关节需要设置:关节的XYZ偏移量。
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- 参数-->
<!-- 参数:
连杆属性:宽度/高度/厚度
关节属性: x y z
-->
<xacro:property name = "camera_length" value = "0.02"> <!-- 厚度 x-->
<xacro:property name = "camera_width" value = "0.05"> <!-- 宽度 y-->
<xacro:property name = "camera_height" value = "0.05"> <!-- 高度z-->
<xacro:property name = "joint_camera_x" value = "0.08">
<xacro:property name = "joint_camera_y" value = "0">
<xacro:property name = "joint_camera_z" value = "${base_length / 2 + camera_height / 2}">
<link name = "camera">
<visual>
<geometry>
<box size = ${camera_length} ${ camera_width} ${camera_height} />
</geometry>
<material name = "black ">
<color rgba = "0 0 0 0.8" />
</material>
</visual>
</link>
<joint name = "camera2base" type = "fixed">
<parent link = "base_link" />
<child link = "camera" />
<origin xyz ="${joint_camera_x} ${joint_camera_y} ${joint_camera_z}" rpy= "0 0 0">
</joint>
</robot>
(2)雷达
雷达包括两部分:雷达本身与雷达支架。以及和摄像头一样,雷达也要设计参数。
如:支架与雷达都是圆柱状,我们要知道它们的半径和高度。并且,支架安装在小车底盘上,雷达安装在支架上,这两种操作都需要joint,这时候就要知道joint的XYZ偏移量。
对于参数,这里我们参考一开始提到的教程中的数值。
支架半径和高度分别为0.01和0.15,雷达半径的长度分别为0.03和0.05,这部分代码如下
<xacro:property name = "support_radius" value = "0.01" />
<xacro:property name = "support_length" value = "0.15" />
<xacro:property name = "laser_radius" value = "0.03" />
<xacro:property name = "laser_length" value = "0.05" />
接下来设置偏移量。首先二者都位于小车正中心的位置,所以XY偏移量都是0,只看Z轴偏移量。
支架的Z轴偏移量是小车底盘高度的一半加上支架高度的一半,雷达相对于支架的偏移量是支架高度的一半加上雷达高度的一半。这部分代码如下:
<xacro:property name = "joint_support_x" value = "0" />
<xacro:property name = "joint_support_y" value = "0" />
<xacro:property name = "joint_support_z" value = "${base_link_length / 2 +support_length / 2}" />
<xacro:property name = "joint_laser_x" value = "0" />
<xacro:property name = "joint_laser_y" value = "0" />
<xacro:property name = "joint_laser_z" value = "${support_length / 2 + laser_length_ / 2}" />
设置完参数再进行雷达和支架相关的link和joint实现:
支架的link实现:要设置支架的半径和高度支架是圆柱所以标签是cylinder,半径和高度都是之前设置好的直接用${}调用。颜色设置为黄色,rgb值为0.8 0.5 0.0,透明度0.5。
<link name ="support">
<visual>
<geometry>
<cylinder radius = "${support_radius}" length = "${support_length}">
</geometry>
<material name = "yellow">
<color rgba = "0.8 0.5 0.0 0.5"/>
</material>
</visual>
</link>
支架的joint实现:支架和小车主体连接,父级link是小车底盘base_link,子级是支架support。偏移量XYZ已经封装好,直接通过${}调用。
<joint name = "support2base" type = "fixed">
<parent link ="base_link" />
<child link = "support"/>
<origin xyz = "${joint_support_x} ${joint_support_y} ${joint_support_z}" rpy ="0 0 0">
</joint>
这样,支架部分就完成了,接下来进行雷达的设置。
雷达的link和joint设置和支架类似,只需要更改一下名称颜色、parent 和child link、偏移量。
<link name ="laser">
<visual>
<geometry>
<cylinder radius = "${laser_radius}" length = "${laser_length}"/>
</geometry>
<material name = "black">
<color rgba = "0 0 0 0.5" />
</material>
</visual>
</link>
<joint name = "laser2support" type = "fixed">
<parent link ="support" />
<child link = "laser"/>
<origin xyz = "${joint_laser_x} ${joint_laser_y} ${joint_laser_z}" rpy ="0 0 0" />
</joint>
至此设置完毕,雷达文件整体代码如下:
<robot name="mycar" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- 雷达部件 -->
<!-- 参数-->
<!-- 支架:
支架尺寸:半径 高度
关节偏移量:xyz
-->
<!-- 雷达:
雷达尺寸:半径 高度
关节偏移量:xyz
-->
<xacro:property name = "support_radius" value = "0.01" />
<xacro:property name = "support_length" value = "0.15" />
<xacro:property name = "laser_radius" value = "0.03" />
<xacro:property name = "laser_length" value = "0.05" />
<xacro:property name = "joint_support_x" value = "0" />
<xacro:property name = "joint_support_y" value = "0" />
<xacro:property name = "joint_support_z" value = "${base_link_length / 2 +support_length / 2}" />
<xacro:property name = "joint_laser_x" value = "0" />
<xacro:property name = "joint_laser_y" value = "0" />
<xacro:property name = "joint_laser_z" value = "${support_length / 2 + laser_length_ / 2}" />
<!-- 支架-->
<link name ="support">
<visual>
<geometry>
<cylinder radius = "${support_radius}" length = "${support_length}"/>
</geometry>
<material name = "yellow">
<color rgba = "0.8 0.5 0.0 0.5" />
</material>
</visual>
</link>
<joint name = "support2base" type = "fixed">
<parent link ="base_link" />
<child link = "support"/>
<origin xyz = "${joint_support_x} ${joint_support_y} ${joint_support_z}" rpy ="0 0 0" />
</joint>
<!-- 雷达-->
<link name ="laser">
<visual>
<geometry>
<cylinder radius = "${laser_radius}" length = "${laser_length}"/>
</geometry>
<material name = "black">
<color rgba = "0 0 0 0.5" />
</material>
</visual>
</link>
<joint name = "laser2support" type = "fixed">
<parent link ="support" />
<child link = "laser"/>
<origin xyz = "${joint_laser_x} ${joint_laser_y} ${joint_laser_z}" rpy ="0 0 0" />
</joint>
</robot>
接下来保存文件后,运行一下代码,看看效果。
milk@milk:~/DEMO05_WS$ source ./devel/setup.bash
milk@milk:~/DEMO05_WS$ roslaunch urdf01_rviz car.launch
好了,到这里Xacro的部分就结束了,接下来是arbotix控制机器人运动~好期待~