ROS学习初探之自建小车模型并进行仿真(二)

tech2022-12-22  187

roslaunch mbot_teleop mbot_teleop.launch # URDF文件转xacro文件,并加入控制插件

一、URDF文件

我们都知道URDF是ROS中机器人模型的描述格式,包含对机器人刚体外观、物理属性、关节类型等方面的描述。我们先看看从SolidWorks中导出的URDF文件。我们打开tianbot_mini_description.urdf:

<?xml version="1.0" encoding="utf-8"?> <!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com) Commit Version: 1.5.1-0-g916b5db Build Version: 1.5.7152.31018 For more information, please see http://wiki.ros.org/sw_urdf_exporter --> <robot name="tianbot_mini_description"> <link name="base_link"> <inertial> <origin xyz="0.025566 -0.0012293 0.024367" rpy="0 0 0" /> <mass value="0.15009" /> <inertia ixx="7.0347E-05" ixy="-2.608E-07" ixz="1.5444E-05" iyy="7.3091E-05" iyz="-1.2084E-06" izz="0.00010959" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/base_link.STL" /> </geometry> <material name=""> <color rgba="1 1 1 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/base_link.STL" /> </geometry> </collision> </link> <link name="left_wheel_link"> <inertial> <origin xyz="-8.8919E-05 -0.0038269 -8.1628E-05" rpy="0 0 0" /> <mass value="0.014111" /> <inertia ixx="2.4055E-06" ixy="5.333E-08" ixz="1.1993E-09" iyy="4.2136E-06" iyz="3.7603E-08" izz="2.4044E-06" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/left_wheel_link.STL" /> </geometry> <material name=""> <color rgba="0.50196 0.50196 0.50196 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/left_wheel_link.STL" /> </geometry> </collision> </link> <joint name="left_wheel_joint" type="continuous"> <origin xyz="0.0015549 0.053866 0.0011204" rpy="0 0 0" /> <parent link="base_link" /> <child link="left_wheel_link" /> <axis xyz="0.028847 0.99937 0.020786" /> </joint> <link name="right_wheel_link"> <inertial> <origin xyz="8.944E-05 0.0038269 7.9359E-05" rpy="0 0 0" /> <mass value="0.014111" /> <inertia ixx="2.4056E-06" ixy="5.3313E-08" ixz="1.0756E-09" iyy="4.2136E-06" iyz="3.7601E-08" izz="2.4044E-06" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/right_wheel_link.STL" /> </geometry> <material name=""> <color rgba="0.50196 0.50196 0.50196 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/right_wheel_link.STL" /> </geometry> </collision> </link> <joint name="right_wheel_joint" type="continuous"> <origin xyz="-0.0015549 -0.053866 -0.0011204" rpy="0 0 0" /> <parent link="base_link" /> <child link="right_wheel_link" /> <axis xyz="0.028847 0.99937 0.020786" /> </joint> <link name="caster_wheel_link"> <inertial> <origin xyz="-0.0021044 -0.0014298 -0.014923" rpy="0 0 0" /> <mass value="0.014141" /> <inertia ixx="2.1919E-06" ixy="3.8453E-07" ixz="8.1679E-08" iyy="2.2221E-06" iyz="6.9274E-09" izz="3.4078E-06" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/caster_wheel_link.STL" /> </geometry> <material name=""> <color rgba="0.75294 0.75294 0.75294 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/caster_wheel_link.STL" /> </geometry> </collision> </link> <joint name="caster_wheel_joint" type="continuous"> <origin xyz="0.067196 -0.0022154 0.011383" rpy="0 0 0" /> <parent link="base_link" /> <child link="caster_wheel_link" /> <axis xyz="-0.0264 0.021537 -0.99942" /> </joint> <link name="casterball_link"> <inertial> <origin xyz="7.0778E-06 -6.9887E-06 -3.6348E-07" rpy="0 0 0" /> <mass value="0.0091741" /> <inertia ixx="6.5492E-07" ixy="-5.0039E-09" ixz="-2.5621E-10" iyy="6.5468E-07" iyz="2.1952E-10" izz="6.4987E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/casterball_link.STL" /> </geometry> <material name=""> <color rgba="0.55686 0.55686 0.55686 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/casterball_link.STL" /> </geometry> </collision> </link> <joint name="casterball_joint" type="revolute"> <origin xyz="0.0063432 0.007688 -0.022315" rpy="0 0 0" /> <parent link="caster_wheel_link" /> <child link="casterball_link" /> <axis xyz="0.71538 -0.69791 -0.033936" /> <limit lower="0" upper="0" effort="0" velocity="0" /> </joint> <link name="lidar_Link"> <inertial> <origin xyz="0.0047077 0.0002084 -0.0069054" rpy="0 0 0" /> <mass value="0.073208" /> <inertia ixx="2.1832E-05" ixy="4.6598E-07" ixz="8.4247E-06" iyy="4.1492E-05" iyz="-3.6568E-07" izz="4.7274E-05" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/lidar_Link.STL" /> </geometry> <material name=""> <color rgba="0.75294 0.75294 0.75294 1" /> </material> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="package://tianbot_mini_description/meshes/lidar_Link.STL" /> </geometry> </collision> </link> <joint name="lidar_joint" type="fixed"> <origin xyz="0.028391 -0.0024308 0.066849" rpy="0 0 0" /> <parent link="base_link" /> <child link="lidar_Link" /> <axis xyz="0 0 0" /> </joint> <gazebo reference="base_link"> <material>Gazebo/Yellow </material> </gazebo> <gazebo reference="right_wheel_link"> <material>Gazebo/Black </material> </gazebo> <gazebo reference="left_wheel_link"> <material>Gazebo/Black </material> </gazebo> <gazebo reference="caster_wheel_link"> <material>Gazebo/Blue </material> </gazebo> <gazebo reference="lidar_Link"> <material>Gazebo/Red </material> </gazebo> </robot>

我们再看看URDF中各个link的关系图: 我们可以看到从SolidWorks导出的URDF文件,已经配置好了物理属性和碰撞属性,可以在gazebo中打开。并且我配置了一下各个link 的颜色,用gazebo打开后就能看到颜色变了。

二、配置xacro文件

我们知道xacro文件是针对URDF模型产生的另一种精简版、可复用、模块化的描述形式。首先创建一个tianbot_mini.urdf.xacro文件,我们在模型< robot>标签中加入xacro的声明:

<?xml version="1.0" encoding="utf-8"?> <robot name="tianbot_mini_description" xmlns:xacro="http://www.ros.org/wiki/xacro">

接着把上面的URDF文件除去最上面两行全部放进去。

添加传动装置

我们的机器人模型可看作一个两轮差速驱动的机器人,通过调节两个轮子的速度比例,完成前进、转向、倒退等动作。此时需要加入驱动机器人运动的动力源,为使用ROS控制驱动机器人,需要在模型中加入transmission元素,将传动装置与joint绑定。

<!-- Transmission is important to link the joints and the controller --> <xacro:macro name="wheel" params="prefix reflect"> <transmission name="${prefix}_wheel_joint_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${prefix}_wheel_joint" > <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> </joint> <actuator name="${prefix}_wheel_joint_motor"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> </xacro:macro> <wheel prefix="left" reflect="1"/> <wheel prefix="right" reflect="-1"/>

添加gazebo控制器插件

我们直接加入gazebo提供的libgazebo_ros_diff_drive.so两轮差速插件,可以将其应用到现有的机器人模型上。

<!-- controller --> <gazebo> <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so"> <rosDebugLevel>Debug</rosDebugLevel> <publishWheelTF>true</publishWheelTF> <robotNamespace>/</robotNamespace> <publishTf>1</publishTf> <publishWheelJointState>true</publishWheelJointState> <alwaysOn>true</alwaysOn> <updateRate>100.0</updateRate> <legacyMode>true</legacyMode> <leftJoint>left_wheel_joint</leftJoint> <rightJoint>right_wheel_joint</rightJoint> <wheelSeparation>0.1</wheelSeparation> <wheelDiameter>0.043</wheelDiameter> <broadcastTF>1</broadcastTF> <wheelTorque>30</wheelTorque> <wheelAcceleration>1.8</wheelAcceleration> <commandTopic>cmd_vel</commandTopic> <odometryFrame>odom</odometryFrame> <odometryTopic>odom</odometryTopic> <robotBaseFrame>base_footprint</robotBaseFrame> </plugin> </gazebo>

注意leftJoint和rightJoint标签中间要输入自己机器人的左右jointname,wheelSeparation和wheelDiameter标签中间要输入自己机器人的轮间距和轮直径。 到现在xacro文件已经配置好了,我们可以看一看总的

<?xml version="1.0" encoding="utf-8"?> <robot name="tianbot_mini_description" xmlns:xacro="http://www.ros.org/wiki/xacro"> <link name="base_link"> <inertial> <origin xyz="0.025566 -0.0012293 0.024367" rpy="0 0 0" /> <mass value="0.15009" /> 。 。 。 中间太长,我给删了 。 。 。 <joint name="lidar_joint" type="fixed"> <origin xyz="0.028391 -0.0024308 0.066849" rpy="0 0 0" /> <parent link="base_link" /> <child link="lidar_Link" /> <axis xyz="0 0 0" /> </joint> <gazebo reference="base_link"> <material>Gazebo/Red </material> </gazebo> <gazebo reference="right_wheel_link"> <material>Gazebo/Black </material> </gazebo> <gazebo reference="left_wheel_link"> <material>Gazebo/Black </material> </gazebo> <gazebo reference="caster_wheel_link"> <material>Gazebo/Blue </material> </gazebo> <!-- Transmission is important to link the joints and the controller --> <xacro:macro name="wheel" params="prefix reflect"> <transmission name="${prefix}_wheel_joint_trans"> <type>transmission_interface/SimpleTransmission</type> <joint name="${prefix}_wheel_joint" > <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> </joint> <actuator name="${prefix}_wheel_joint_motor"> <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> </xacro:macro> <wheel prefix="left" reflect="1"/> <wheel prefix="right" reflect="-1"/> <!-- controller --> <gazebo> <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so"> <rosDebugLevel>Debug</rosDebugLevel> <publishWheelTF>true</publishWheelTF> <robotNamespace>tianbot_mini</robotNamespace> <publishTf>1</publishTf> <publishWheelJointState>true</publishWheelJointState> <alwaysOn>true</alwaysOn> <updateRate>100.0</updateRate> <legacyMode>true</legacyMode> <leftJoint>left_wheel_joint</leftJoint> <rightJoint>right_wheel_joint</rightJoint> <wheelSeparation>0.1</wheelSeparation> <wheelDiameter>0.043</wheelDiameter> <broadcastTF>1</broadcastTF> <wheelTorque>30</wheelTorque> <wheelAcceleration>1.8</wheelAcceleration> <commandTopic>cmd_vel</commandTopic> <odometryFrame>odom</odometryFrame> <odometryTopic>odom</odometryTopic> <robotBaseFrame>base_footprint</robotBaseFrame> </plugin> </gazebo> </robot>

现在的xacro文件可以通过launch文件打开,并且用键盘控制节点进行小车的控制,这些我们放到下一话再讲。

小结

本节我们简单了解了一下URDF文件和xacro文件,并且说明了如何配置二轮差速小车在gazebo环境中的控制器插件,也就是简单了解一下ros_control。 下一节,由我来说一说配置launch文件和yaml文件,并在gazebo环境中实现对小车的控制,并调用激光雷达插件,在rviz中看到点云数据。 接下去的内容会在古月居的论坛,tianbot_mini板块中同步更新,敬请期待。

参考资料

1.古月老师的<<ROS机器人开发实践>>

最新回复(0)