[Exploring ROS with a 2 Wheeled Robot]2.添加xacro文件

1.xacro文件内导入另一个xacro文件

原来:
在这里插入图片描述
m2wr.xacro文件囊括了m2wr机器人的所有属性,可以按照不同属性的类别进行分块,再建xacro文件,将不同类别的代码导入进去。

1.1创建一个新的materials.xacro文件,将机器人材质部分代码导入

如图:
在这里插入图片描述

1.2导入xacro文件(材质)

1.2.1导入至父xacro文件内

然后修改m2wr.xacro(父xacro)的材质部分(导入新的xacro文件)
在这里插入图片描述

1.2.2 导入至launch文件内

原:
在这里插入图片描述
现:
在这里插入图片描述
修改cat为$(find xacro)/xacro.py

1.2.3介绍下robot_description的意思

就比如1.2.2中的图:
这句话的目的是给 robot_description赋值,从而使得rviz通过robo_description获得机器人模型。
赋的值为:’$ (find xacro)/xacro --inorder’ 在输入参数’为’$ (arg model)’ 情况下的的运行结果。
这是在父launch文件(描述一个机器人的形状)中,后面的文件只要用到了.xacro形式的文件,必须添上这样一句。

1.3导入gazebo文件

原:
在这里插入图片描述
注意!导入的是gazebo标签内的

1.2.1 创建.gazebo文件

现:
创建一个m2wr.gazebo文件,将m2wr文件中的gazebo部分导入进去。
在这里插入图片描述
功能:1.机器人各部件在gazebo中显示的颜色以及2.驱动机器人运动的文件。

1.2.2 导入父xacro文件

在这里插入图片描述

1.4部件部分模块化

原:
在这里插入图片描述

1.4对机器人部件的处理

1.4.1创建一个macros.xacro文件

将机器人的轮子属性(只是轮子,不包含其与主体部分的相对位置,位置信息在父文件中定义)导入进去
首先设置:
1.添加一个macro的标签
2.注意!此处修改了<robot标签

<?xml version="1.0" ?>
<robot>
	<macro name="link_wheel" params="name">
................

	</macro>
</robot>


1.4.2导入一个轮

然后对内部导入一个轮的信息:

<?xml version="1.0" ?>
<robot>
    <macro name="link_wheel" params="name">
        <link name="link_right_wheel">
            <inertial>
            <mass value="0.2"/>
            <origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
            <inertia ixx="0.000526666666667" ixy="0" ixz="0" iyy="0.000526666666667" iyz="0" izz="0.001"/>
            </inertial>
            <collision name="link_right_wheel_collision">
            <origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
            <geometry>
                <cylinder length="0.04" radius="0.1"/>
            </geometry>
            </collision>
            <visual name="link_right_wheel_visual">
            <origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
            <geometry>
                <cylinder length="0.04" radius="0.1"/>
            </geometry>
            </visual>
        </link>
    </macro>
</robot>

1.4.3将名字修改为一个变量,这样,一段程序就可以添加多个轮

如图,1.将<link name = “link_right_wheel” 修改为 <link name=“${name}”
2.内部涉及到name的也同样如此修改
在这里插入图片描述

1.4.4在父文件内应用

1.直接一句:<xacro:link_wheel name=“link_right_wheel”/
就省了图片中左轮的那大段内容
<xacro: 被导入的xacro文件中,想要导入对应的属性部分的name,然后就导入了。
后面的name 就是 子xacro文件的变量了
在这里插入图片描述
2.导入子xacro文件到父xacro文件内
在这里插入图片描述

1.5在宏(macros)里定义轮子的位置(对joint进行宏定义)

1.5.1将某个宏调整为公共的宏(子文件调整)

原:

  <joint name="joint_right_wheel" type="continuous">
    <origin rpy="0 0 0" xyz="-0.05 0.15 0"/>
    <child link="link_right_wheel"/>
    <parent link="link_chassis"/>
    <axis rpy="0 0 0" xyz="0 1 0"/>
    <limit effort="10000" velocity="1000"/>
    <joint_properties damping="1.0" friction="1.0"/>
  </joint>

现:
1.加一个宏定义标签<macro name= params
params 内部可选择的范围是 该宏定义内部的标签,想改哪个标签,放哪个,比如需要修改name child origin_xyz
2.希望修改的标签要在对应的部分改成${ }方式,内部就是一个变量形式。


      <macro name="joint_wheel" params="name child origin_xyz">
        <joint name="${name}" type="continuous">
            <origin rpy="0 0 0" xyz="${origin_xyz}"/>
            <child link="${child}"/>
            <parent link="link_chassis"/>
            <axis rpy="0 0 0" xyz="0 1 0"/>
            <limit effort="10000" velocity="1000"/>
            <joint_properties damping="1.0" friction="1.0"/>
         </joint>
    </macro>
 

1.5.2 在父文件中应用

1.删除之前的joint部分
2.添加宏,给宏对应的值

  <xacro:joint_wheel name="joint_right_wheel" child="link_right_wheel" origin_xyz="-0.05 0.20 0" />

2启动

出现bug
在这里插入图片描述
首先:对launch文件进行修改:
在这里插入图片描述

< param name=“robot_description” command="$(find xacro)/xacro
去掉原来xacro.py中的.py

接着,还有bug

经搜索进行如下对所有文件修改:
在这里插入图片描述
还有一些细节错误,不一一展示了,最终运行成功
在这里插入图片描述

附录。附上所有代码!

1.spawn.launch

<?xml version="1.0" encoding="UTF-8"?>
<launch>
    <param name="robot_description" command="$(find xacro)/xacro  '$(find m2wr_description)/urdf/m2wr.xacro'"/>

    <arg name="x" default="0"/>
    <arg name="y" default="0"/>
    <arg name="z" default="0.5"/>

    <node name="mybot_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
          args="-urdf -param robot_description -model m2wr -x $(arg x) -y $(arg y) -z $(arg z)" />
          
    <!-- these are the arguments you can pass this launch file, for example paused:=true -->
    <arg name="paused" default="false"/>
    <arg name="use_sim_time" default="true"/>
    <arg name="gui" default="true"/>
    <arg name="headless" default="false"/>
    <arg name="debug" default="false"/>
 
    <!-- We resume the logic in empty_world.launch -->
    <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="debug" value="$(arg debug)" />
    <arg name="gui" value="$(arg gui)" />
    <arg name="paused" value="$(arg paused)"/>
    <arg name="use_sim_time" value="$(arg use_sim_time)"/>
    <arg name="headless" value="$(arg headless)"/>
    <!-- arg name="world_name" value="$(find task_1)/world/tutorial_testing.world"/ -->
    </include>

</launch>

2.m2wr.xacro

<?xml version="1.0" ?>
<robot name="m2wr" xmlns:xacro="http://www.ros.org/wiki/xacro">

  <xacro:include filename = "$(find m2wr_description)/urdf/materials.xacro"/>
  <xacro:include filename="$(find m2wr_description)/urdf/m2wr.gazebo" />
  <xacro:include filename="$(find m2wr_description)/urdf/macros.xacro" />

  
  <link name="link_chassis">
    <!-- pose and inertial -->
    <pose>0 0 0.1 0 0 0</pose>
    <inertial>
      <mass value="5"/>
      <origin rpy="0 0 0" xyz="0 0 0.1"/>
      <inertia ixx="0.0395416666667" ixy="0" ixz="0" iyy="0.106208333333" iyz="0" izz="0.106208333333"/>
    </inertial>
    <!-- body -->
    <collision name="collision_chassis">
      <geometry>
        <box size="0.5 0.3 0.07"/>
      </geometry>
    </collision>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="0.5 0.3 0.07"/>
      </geometry>
      <material name="blue"/>
    </visual>
    <!-- caster front -->
    <collision name="caster_front_collision">
      <origin rpy=" 0 0 0" xyz="0.35 0 -0.05"/>
      <geometry>
        <sphere radius="0.05"/>
      </geometry>
      <surface>
        <friction>
          <ode>
            <mu>0</mu>
            <mu2>0</mu2>
            <slip1>1.0</slip1>
            <slip2>1.0</slip2>
          </ode>
        </friction>
      </surface>
    </collision>
    <visual name="caster_front_visual">
      <origin rpy=" 0 0 0" xyz="0.2 0 -0.05"/>
      <geometry>
        <sphere radius="0.05"/>
      </geometry>
    </visual>
  </link>
  

  <xacro:link_wheel name="link_right_wheel"/>
  <xacro:joint_wheel name="joint_right_wheel" child="link_right_wheel" origin_xyz="-0.05 0.20 0" />
    
  <xacro:link_wheel name="link_left_wheel"/>
  <xacro:joint_wheel name="joint_left_wheel" child="link_left_wheel" origin_xyz="-0.05 -0.20 0" />

</robot>

3.materials.xacro

<?xml version="1.0" ?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  <material name="black">
    <color rgba="0.0 0.0 0.0 1.0"/>
  </material>
  <material name="blue">
    <color rgba="0.203125 0.23828125 0.28515625 1.0"/>
  </material>
  <material name="green">
    <color rgba="0.0 0.8 0.0 1.0"/>
  </material>
  <material name="grey">
    <color rgba="0.2 0.2 0.2 1.0"/>
  </material>
  <material name="orange">
    <color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
  </material>
  <material name="brown">
    <color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
  </material>
  <material name="red">
    <color rgba="0.80078125 0.12890625 0.1328125 1.0"/>
  </material>
  <material name="white">
    <color rgba="1.0 1.0 1.0 1.0"/>
  </material>
</robot>

4.m2wr.gazebo

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

  <gazebo reference="link_chassis">
    <material>Gazebo/Orange</material>
  </gazebo>
  <gazebo reference="link_left_wheel">
    <material>Gazebo/Blue</material>
  </gazebo>
  <gazebo reference="link_right_wheel">
    <material>Gazebo/Blue</material>
  </gazebo>
  
  <gazebo>
    <plugin filename="libgazebo_ros_diff_drive.so" name="differential_drive_controller">
      <alwaysOn>true</alwaysOn>
      <updateRate>20</updateRate>
      <leftJoint>joint_left_wheel</leftJoint>
      <rightJoint>joint_right_wheel</rightJoint>
      <wheelSeparation>0.4</wheelSeparation>
      <wheelDiameter>0.2</wheelDiameter>
      <torque>0.1</torque>
      <commandTopic>cmd_vel</commandTopic>
      <odometryTopic>odom</odometryTopic>
      <odometryFrame>odom</odometryFrame>
      <robotBaseFrame>link_chassis</robotBaseFrame>
    </plugin>
  </gazebo>
 </robot> 

5.macros.xacro

<?xml version="1.0" ?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
    <xacro:macro name="link_wheel" params="name">
        <link name="${name}">
            <inertial>
            <mass value="0.2"/>
            <origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
            <inertia ixx="0.000526666666667" ixy="0" ixz="0" iyy="0.000526666666667" iyz="0" izz="0.001"/>
            </inertial>
            <collision name="${name}_collision">
            <origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
            <geometry>
                <cylinder length="0.04" radius="0.1"/>
            </geometry>
            </collision>
            <visual name="${name}_visual">
            <origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
            <geometry>
                <cylinder length="0.04" radius="0.1"/>
            </geometry>
            </visual>
        </link>
    </xacro:macro>
    
   <xacro:macro name="joint_wheel" params="name child origin_xyz">
        <joint name="${name}" type="continuous">
            <origin rpy="0 0 0" xyz="${origin_xyz}"/>
            <child link="${child}"/>
            <parent link="link_chassis"/>
            <axis rpy="0 0 0" xyz="0 1 0"/>
            <limit effort="10000" velocity="1000"/>
            <joint_properties damping="1.0" friction="1.0"/>
         </joint>
    </xacro:macro>
    
    
    
</robot>

  • 1
    点赞
  • 5
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值