第四章、用xacro优化URDF并配置gazebo仿真插件
1►前言
上节用简易模型写了一个小车的URDF代码,这一节将用xacro对其进行优化,这里我并不打算用宏对参数进行封装,因为我个人觉得这样看起来会比较直观,方便读者阅读。
2►配置主xacro文件
新建racecar.xacro文件,将上一节racebot.urdf中的代码复制过来并进行修改,整体代码如下:
<?xml version="1.0" encoding="utf-8"?>
<robot name="racebot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find racebot_description)/urdf/ackermann/macros.xacro" />
<link name="base_footprint">
</link>
<link name="base_link">
<visual>
<geometry>
<box size="0.28 0.1 0.03"/>
<!-- <mesh filename="package://tianracer_description/meshes/base_link.STL" /> -->
</geometry>
<!-- <origin xyz="0 0 -0.023" rpy="0 0 0" /> -->
<origin xyz="0 0 0" rpy="0 0 0" />
<material name="yellow">
<color rgba="0.8 0.3 0.1 0.5" />
</material>
</visual>
<collision>
<geometry>
<box size="0.28 0.1 0.03" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
</link>
<joint name="base_link2base_footprint" type="fixed">
<parent link="base_footprint" />
<child link="base_link"/>
<origin xyz="0 0 0.032" rpy="0 0 0" />
</joint>
<link name="base_inertia">
<inertial>
<origin xyz="0 0 0" />
<mass value="4" />
<inertia ixx="0.0264" ixy="0" ixz="0" iyy="0.0294" iyz="0" izz="0.00364" />
</inertial>
</link>
<joint name="chassis_inertia_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_link" />
<child link="base_inertia" />
</joint>
<link name="left_steering_hinge">
<visual>
<geometry>
<cylinder radius="0.01" length="0.005" />
<!-- <sphere radius="0.015" /> -->
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.01" length="0.005" />
<!-- <sphere radius="0.015" /> -->
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0" />
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.5" />
<inertia ixx="1.35E-05" ixy="0" ixz="0" iyy="1.35E-05" iyz="0" izz="2.5E-05" />
</inertial>
</link>
<joint name="left_steering_hinge_joint" type="revolute">
<parent link="base_link" />
<child link="left_steering_hinge" />
<origin xyz="0.13 0.065 0" />
<axis xyz="0 0 1" />
<limit lower="-0.6" upper="0.6" effort="5.0" velocity="1000.0"/>
</joint>
<xacro:steering_hinge_transmission name="left_steering_hinge" />
<link name="left_front_wheel">
<visual>
<geometry>
<cylinder radius="0.033" length="0.02" />
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.032" length="0.02" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0" />
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="2.0" />
<inertia ixx="6.64E-04" ixy="0" ixz="0" iyy="6.64E-04" iyz="0" izz="1.02E-03" />
</inertial>
</link>
<joint name="left_front_wheel_joint" type="continuous">
<parent link="left_steering_hinge" />
<child link="left_front_wheel" />
<origin xyz="0 0.025 0" />
<axis xyz="0 1 0" />
<limit effort="10" velocity="1000" />
</joint>
<xacro:wheel_transmission name="left_front_wheel" />
<link name="right_steering_hinge">
<visual>
<geometry>
<cylinder radius="0.01" length="0.005" />
</geometry>
<origin xyz="0 0 0" rpy="1.57 0 0" />
<material name="black">
<color rgba="0.0 0.0 0.0 1.0" />
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.01" length="0.005" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="1.57 0.0 0.0" />
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.5" />
<inertia ixx="1.35E-05" ixy="0" ixz="0" iyy="1.35E-05" iyz="0" izz="2.5E-05" />
</inertial>
</link>
<joint name="right_steering_hinge_joint" type="revolute">
<parent link="base_link" />
<child link="right_steering_hinge" />
<origin xyz="0.13 -0.065 0" />
<axis xyz="0 0 1" />
<limit lower="-0.6" upper="0.6" effort="5.0" velocity="1000.0"/>
</joint>
<xacro:steering_hinge_transmission name="right_steering_hinge" />
<link name="right_front_wheel&#