在阅读本文之前,推荐阅读前篇ROS机器人TF基础和全部资料文档:
- TF基础:https://blog.csdn.net/ZhangRelay/article/details/108374509
- 全文档:https://blog.csdn.net/ZhangRelay/article/details/108192167
所有内容均在ROS1 indigo,kinetic,melodic,noetic以及ROS2 dashing,foxy等测试通过。 但介绍以noetic和foxy为主。
在ROS中自定义机器人的3D模型
机器人模型通常为移动机器人和工业机械臂,那么如果在rviz中进行三维可视化的URDF模型设计呢? 先看如下两副截图(点击可看大图,细节清晰): 参考命令:
- ros2 launch urdf_tutorial display.launch.py model:=/home/ros/RobCode/urdf_tutorial/src/urdf/magician.urdf
/\/\/\移动机器人案例如上/\/\/\ 参考命令:
- ros2 launch urdf_tutorial display.launch.py model:=/home/ros/RobCode/urdf_tutorial/src/urdf/cozmo2.urdf
/\/\/\工业机械臂案例如上/\/\/\ 可以看到机器人各关节的坐标以及非常精细的模型,并可以通过人机交互面板(joint_state_publisher)控制其状态。 由此可知: 相比于仿真,虽然直接在一个真正的机器人上进行编程能够给我们最佳的反馈,并且也更加令人激动,但是并不是每个人都有机会接触到真正的机器人。基于这个原因,我们需要对整个物理世界进行建模与仿真。机器人三维模型或部分结构模型主要用于仿真机器人或者为了帮助开发者简化他们的常规工作,在ROS中通过URDF文件实现。标准化机器人描述格式(Unified Robot Description Format , URDF)是一种用于描述机器人及其部分结构、关节、自由度等的XML格式文件。每次在ROS系统中看到3D机器人都会有URDF文件与之对应,例如PR2(Willow Garage)或者Robonaut(NASA)。在下面的章节中我们将会学习如何创建这种文件和格式用于定义不同的值。
此部分介绍在ROSwiki中,不在此赘述。URDF模型在ROS1和ROS2中通用。 特别注意两者launch文件差别: ros1(indigo,kinetic,melodic,noetic):
<launch>
<arg name="model" default="$(find urdf_tutorial)/urdf/01-myfirst.urdf"/>
<arg name="gui" default="true" />
<arg name="rvizconfig" default="$(find urdf_tutorial)/rviz/urdf.rviz" />
<param name="robot_description" command="$(find xacro)/xacro $(arg model)" />
<node if="$(arg gui)" name="joint_state_publisher" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" />
<node unless="$(arg gui)" name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />
</launch>
ros2(dashing,foxy):
import launch
from launch.substitutions import Command, LaunchConfiguration
import launch_ros
import os
def generate_launch_description():
pkg_share = launch_ros.substitutions.FindPackageShare(package='urdf_tutorial').find('urdf_tutorial')
default_model_path = os.path.join(pkg_share, 'urdf/01-myfirst.urdf')
default_rviz_config_path = os.path.join(pkg_share, 'rviz/urdf.rviz')
robot_state_publisher_node = launch_ros.actions.Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[{'robot_description': Command(['xacro ', LaunchConfiguration('model')])}]
)
joint_state_publisher_node = launch_ros.actions.Node(
package='joint_state_publisher',
executable='joint_state_publisher',
name='joint_state_publisher',
condition=launch.conditions.UnlessCondition(LaunchConfiguration('gui'))
)
joint_state_publisher_gui_node = launch_ros.actions.Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
name='joint_state_publisher_gui',
condition=launch.conditions.IfCondition(LaunchConfiguration('gui'))
)
rviz_node = launch_ros.actions.Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', LaunchConfiguration('rvizconfig')],
)
return launch.LaunchDescription([
launch.actions.DeclareLaunchArgument(name='gui', default_value='True',
description='Flag to enable joint_state_publisher_gui'),
launch.actions.DeclareLaunchArgument(name='model', default_value=default_model_path,
description='Absolute path to robot urdf file'),
launch.actions.DeclareLaunchArgument(name='rvizconfig', default_value=default_rviz_config_path,
description='Absolute path to rviz config file'),
joint_state_publisher_node,
joint_state_publisher_gui_node,
robot_state_publisher_node,
rviz_node
])
掌握此部分内容非常重要,更具体的讲解参考如下链接:
- ROS 2启动-launch-:https://blog.csdn.net/ZhangRelay/article/details/103498784
- 机器人+复杂环境案例:https://blog.csdn.net/ZhangRelay/article/details/105707950
那么开始创建第一个URDF案例吧!
创建第一个URDF文件
一个四轮小车模型如下:
其urdf代码为:
<?xml version="1.0" ?>
<robot name="robot1_xacro" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor">
<link name="base_footprint">
<visual>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
</visual>
<inertial>
<mass value="0.0001"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<gazebo reference="base_footprint">
<material>Gazebo/Green</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 0"/>
<parent link="base_footprint"/>
<child link="base_link"/>
</joint>
<link name="base_link">
<visual>
<geometry>
<box size="0.2 .3 .1"/>
</geometry>
<origin rpy="0 0 1.54" xyz="0 0 0.05"/>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.2 .3 0.1"/>
</geometry>
</collision>
<inertial>
<mass value="10"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<link name="wheel_1">
<visual>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<link name="wheel_2">
<visual>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<link name="wheel_3">
<visual>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<link name="wheel_4">
<visual>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
<origin rpy="0 0 0" xyz="0 0 0"/>
<material name="black"/>
</visual>
<collision>
<geometry>
<cylinder length="0.05" radius="0.05"/>
</geometry>
</collision>
<inertial>
<mass value="1"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="base_to_wheel1" type="continuous">
<parent link="base_link"/>
<child link="wheel_1"/>
<origin rpy="1.5707 0 0" xyz="0.1 0.15 0"/>
<axis xyz="0 0 1"/>
</joint>
<joint name="base_to_wheel2" type="continuous">
<axis xyz="0 0 1"/>
<anchor xyz="0 0 0"/>
<limit effort="100" velocity="100"/>
<parent link="base_link"/>
<child link="wheel_2"/>
<origin rpy="1.5707 0 0" xyz="-0.1 0.15 0"/>
</joint>
<joint name="base_to_wheel3" type="continuous">
<parent link="base_link"/>
<axis xyz="0 0 1"/>
<child link="wheel_3"/>
<origin rpy="1.5707 0 0" xyz="0.1 -0.15 0"/>
</joint>
<joint name="base_to_wheel4" type="continuous">
<parent link="base_link"/>
<axis xyz="0 0 1"/>
<child link="wheel_4"/>
<origin rpy="1.5707 0 0" xyz="-0.1 -0.15 0"/>
</joint>
</robot>
简单解释一下,如需了解更全面具体的内容参考(wiki.ros.org/urdf/XML)。 这些URDF代码是基于XML的,这种格式并不强制缩进,但还是建议大家这么做。因此,建议大家使用一个支持缩进的编辑器或者找到适当插件并进行配置(例如,比较好的是Vim中的.vimrc文件)。
解释文件格式
如在代码中所见,有两种用于描述机器人几何结构的基本字段:连接(link)和关节(joint)。 如连接的名字是base_link(本体连接),这个名称在文件中必须唯一。
<link name="base_link">
<visual>
<geometry>
<box size="0.2 .3 .1"/>
</geometry>
<origin rpy="0 0 1.54" xyz="0 0 0.05"/>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.2 .3 0.1"/>
</geometry>
</collision>
<inertial>
<mass value="10"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
为了定义我们在仿真环境中的物体,在前面的代码中使用了visual字段。在代码中你能够定义几何形状(圆柱体、立方体、球体和纹理网格)、材质(颜色和纹理)和原点。 然后使用以下代码定义关节:
<joint name="base_to_wheel1" type="continuous">
<parent link="base_link"/>
<child link="wheel_1"/>
<origin rpy="1.5707 0 0" xyz="0.1 0.15 0"/>
<axis xyz="0 0 1"/>
</joint>
在joint字段中,我们先定义名称(名称要求唯一)。然后定义关节类型(固定关节fixed,转动关节revolute,旋转关节continuous,自由度浮动关节floating,或平面运动关节planar),以及父连接坐标系和子连接坐标系(关节相连的前后坐标系)。在本例中,wheel_1是base_link的子连接坐标系。它是固定关节(fixed),但如果这个关节是一个轮轴,那么我们可以设置其为转动关节(revolute)。 关于urdf各类工具如check,tf等自行探索实践! 使用如下命令查看模型: ros2 launch urdf_tutorial display.launch.py model:=/home/ros/RobCode/urdf_tutorial/src/urdf/robot1_base1.urdf 如果使用ros1,将ros2 launch替换为roslaunch即可。 ROS1的urdf模型都可以直接移植到ROS2中,需要修改的代码非常少,主要为launch和其他配置文件,如功能包名称以及纹理材质配置的路径等。
加载纹理网格到机器人模型
以ROS1的cozmo模型为例:
<?xml version="1.0"?>
<robot name="AnkiCozmo" xmlns:xacro="http://ros.org/wiki/xacro">
<!--XACRO for intertial -->
<xacro:macro name="cylinder_inertial" params="radius length mass">
<inertial>
<mass value="${mass}" />
<inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
izz="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
iyy="${0.5 * mass * radius * radius}" />
</inertial>
</xacro:macro>
<xacro:macro name="box_inertial" params="mass x y z">
<inertial>
<mass value="${mass}" />
<inertia ixx="${mass*(y*y+z*z)/12}" ixy = "0" ixz = "0" iyy="${mass*(x*x+z*z)/12}" iyz = "0" izz="${mass*(x*x+z*z)/12}" />
</inertial>
</xacro:macro>
<xacro:macro name="box_inertial_default" params="mass">
<inertial>
<mass value="${mass}" />
<inertia ixx="0.000001" ixy = "0" ixz = "0" iyy="0.000001" iyz = "0" izz="0.0000001" />
</inertial>
</xacro:macro>
<!-- LINKS =========================== -->
<!--chassis-->
<link name="base_link">
<xacro:box_inertial mass="0.06" x="0.073" y="0.043" z="0.061" />
<visual>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/body3.dae" />
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/body3.dae" />
</geometry>
</collision>
</link>
<!--Front left wheel-->
<link name="front_left_wheel">
<xacro:cylinder_inertial mass="0.005" radius="0.01314" length="0.01167"/>
<visual>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/flw2.dae" />
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/flw2.dae" />
</geometry>
</collision>
</link>
<!--Front right wheel -->
<link name="front_right_wheel">
<xacro:cylinder_inertial mass="0.005" radius="0.01314" length="0.01167"/>
<visual>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/flw2.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/flw2.dae"/>
</geometry>
</collision>
</link>
<!--Rear left wheel -->
<link name="rear_left_wheel">
<xacro:cylinder_inertial mass="0.005" radius="0.008995" length="0.01167"/>
<visual>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/rlw2.dae" />
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/rlw2.dae"/>
</geometry>
</collision>
</link>
<!--Rear right wheel -->
<link name="rear_right_wheel">
<xacro:cylinder_inertial mass="0.005" radius="0.008995" length="0.01167"/>
<visual>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/rlw2.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/rlw2.dae"/>
</geometry>
</collision>
</link>
<!-- Head -->
<link name="head">
<xacro:box_inertial mass="0.01" x="0.036" y="0.038" z="0.041" />
<visual>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/head_screen.dae" />
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/head_screen.dae"/>
</geometry>
</collision>
</link>
<!-- lifter -->
<link name="full_lift">
<inertial>
<origin xyz="0.025 0 0"/>
<mass value="0.01" />
<inertia ixx="0.000004887" ixy = "0" ixz = "0" iyy="0.000007551" iyz = "0" izz="0.000007551" />
</inertial>
<!-- <xacro:box_inertial mass="0.01" x="0.081" y="0.058" z="0.050"/> -->
<visual>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/lift3.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/lift3.dae"/>
</geometry>
</collision>
</link>
<!-- Belts -->
<link name="left_belt">
<xacro:box_inertial_default mass="0.0001"/>
<visual>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/belt.dae" />
</geometry>
</visual>
</link>
<link name="right_belt">
<xacro:box_inertial_default mass="0.0001"/>
<visual>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/belt.dae" />
</geometry>
</visual>
</link>
<!-- sensors links -->
<link name="camera_link">
<visual>
<geometry>
<box size="0.005 0.005 0.005"/>
</geometry>
</visual>
</link>
<link name="drop_ir">
<visual>
<geometry>
<box size="0.005 0.005 0.005"/>
</geometry>
</visual>
</link>
<!--
<link name="imu">
<visual>
<geometry>
<box size="0.005 0.005 0.005"/>
</geometry>
</visual>
</link>
-->
<!-- JOINTS ====================================-->
<joint name="base_to_lift" type="revolute">
<parent link="base_link"/>
<child link="full_lift"/>
<origin xyz="-0.005 0 0.013"/>
<limit lower="-0.8" upper="0" effort="5" velocity="10"/>
<axis xyz="0 1 0"/>
</joint>
<joint name="base_to_head" type="revolute">
<parent link="base_link"/>
<child link="head"/>
<origin xyz="0.015 0 0.02"/>
<limit lower="-0.52" upper="0.17" effort="100" velocity="10"/>
<dynamics damping="10" friction="1"/>
<axis xyz="0 1 0"/>
</joint>
<joint name="base_to_flw" type="continuous">
<parent link="base_link"/>
<child link="front_left_wheel"/>
<origin xyz="0.03 0.024 -0.012"/>
<axis xyz="0 1 0"/>
</joint>
<joint name="base_to_frw" type="continuous">
<parent link="base_link"/>
<child link="front_right_wheel"/>
<origin xyz="0.03 -0.024 -0.012"/>
<axis xyz="0 1 0"/>
</joint>
<joint name="base_to_rlw" type="continuous">
<parent link="base_link"/>
<child link="rear_left_wheel"/>
<origin xyz="-0.017 0.024 -0.012"/>
<axis xyz="0 1 0"/>
</joint>
<joint name="base_to_rrw" type="continuous">
<parent link="base_link"/>
<child link="rear_right_wheel"/>
<origin xyz="-0.017 -0.024 -0.012"/>
<axis xyz="0 1 0"/>
</joint>
<joint name="head_camera_joint" type="fixed">
<parent link="head"/>
<child link="camera_link"/>
<origin xyz="0.07 0 0.0" rpy="0 0 0"/>
</joint>
<joint name="drop_ir_joint" type="fixed">
<parent link="base_link"/>
<child link="drop_ir"/>
<origin xyz="0 0 0" rpy="0 1.57 0" />
</joint>
<!--
<joint name="imu_joint" type="fixed">
<parent link="head"/>
<child link="imu"/>
<origin xyz="0.0 0 0.0" rpy="0 0 0" />
</joint>
-->
<joint name="wheel_left_belt" type="fixed">
<parent link="base_link"/>
<child link="left_belt"/>
<origin xyz="0.01 0.024 -0.012"/>
</joint>
<joint name="wheel_right_belt" type="fixed">
<parent link="base_link"/>
<child link="right_belt"/>
<origin xyz="0.01 -0.024 -0.012"/>
</joint>
<!-- Transmissions for joints -->
<transmission name="base_to_head_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_to_head">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="base_to_headMotor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="base_to_lift_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="base_to_lift">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="base_to_liftMotor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- GAZEBO RELATED PART -->
<!-- ROS Control plugin for Gazebo -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/cozmo</robotNamespace>
</plugin>
</gazebo>
<gazebo reference="camera_link">
<sensor type="camera" name="cozmo_camera">
<update_rate>10.0</update_rate>
<camera name="headcamera">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>400</width>
<height>400</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.01</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>10.0</updateRate>
<cameraName>cozmo_camera</cameraName>
<imageTopicName>image</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
<gazebo reference="drop_ir">
<sensor type="ray" name="TeraRanger">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>50</update_rate>
<ray>
<scan>
<horizontal>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.14835</min_angle>
<max_angle>0.14835</max_angle>
</horizontal>
<vertical>
<samples>10</samples>
<resolution>1</resolution>
<min_angle>-0.14835</min_angle>
<max_angle>0.14835</max_angle>
</vertical>
</scan>
<range>
<min>0.01</min>
<max>2</max>
<resolution>0.02</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>50</updateRate>
<topicName>drop_sensor</topicName>
<frameName>drop_ir</frameName>
<radiation>INFRARED</radiation>
<fov>0.2967</fov>
</plugin>
</sensor>
</gazebo>
<!--IMU gazebo-->
<gazebo reference="imu">
<gravity>true</gravity>
<sensor name="imu_sensor" type="imu">
<always_on>true</always_on>
<update_rate>100</update_rate>
<visualize>true</visualize>
<topic>__default_topic__</topic>
<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
<topicName>imu</topicName>
<bodyName>imu</bodyName>
<updateRateHZ>10.0</updateRateHZ>
<gaussianNoise>${0.0017*0.0017}</gaussianNoise>
<xyzOffset>0 0 0</xyzOffset>
<rpyOffset>0 0 0</rpyOffset>
<frameName>imu</frameName>
</plugin>
<pose>0 0 0 0 0 0</pose>
</sensor>
</gazebo>
<!--
<gazebo reference="rear_right_wheel">
<mu1>100000</mu1>
<mu2>100000</mu2>
</gazebo>
<gazebo reference="rear_left_wheel">
<mu1>100000</mu1>
<mu2>100000</mu2>
</gazebo>
<gazebo reference="front_right_wheel">
<mu1>100000</mu1>
<mu2>100000</mu2>
</gazebo>
<gazebo reference="front_left_wheel">
<mu1>100000</mu1>
<mu2>100000</mu2>
</gazebo>
-->
<gazebo>
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
<updateRate>25.0</updateRate>
<robotNamespace>/</robotNamespace>
<leftFrontJoint>base_to_flw</leftFrontJoint>
<rightFrontJoint>base_to_frw</rightFrontJoint>
<leftRearJoint>base_to_rlw</leftRearJoint>
<rightRearJoint>base_to_rrw</rightRearJoint>
<wheelSeparation>0.048</wheelSeparation>
<wheelDiameter>0.04</wheelDiameter>
<robotBaseFrame>base_link</robotBaseFrame>
<torque>20</torque>
<topicName>cmd_vel</topicName>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<broadcastTF>1</broadcastTF>
</plugin>
</gazebo>
</robot>
注意,加载纹理的部分:
<!--chassis-->
<link name="base_link">
<xacro:box_inertial mass="0.06" x="0.073" y="0.043" z="0.061" />
<visual>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/body3.dae" />
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/body3.dae" />
</geometry>
</collision>
</link>
对应文件为:
有时候希望自己构建的模型能够更加真实,并不是说简单地增加更多的基本几何形状和模块,而是通过添加更多的现实元素使模型变得更加丰富和细致。这就需要加载我们自行创建的纹理网格(mesh)或者使用其他机器人模型的纹理网格。URDF模型支持.stl和.dae格式的纹理网格。
使机器人模型运动
为了将模型转换成能实际运动的机器人,我们唯一需要做的是检查好所选用的关节类型。如果你检查URDF模型文件,将会看到我们在模型中使用了不同类型的关节。 要判断关节的轴或转动限值是否合适,有一种好的办法就是使用Join_State_Publisher图形化用户界面(GUI)。
<joint name="base_to_lift" type="revolute">
<parent link="base_link"/>
<child link="full_lift"/>
<origin xyz="-0.005 0 0.013"/>
<limit lower="-0.8" upper="0" effort="5" velocity="10"/>
<axis xyz="0 1 0"/>
</joint>
<joint name="base_to_head" type="revolute">
<parent link="base_link"/>
<child link="head"/>
<origin xyz="0.015 0 0.02"/>
<limit lower="-0.52" upper="0.17" effort="100" velocity="10"/>
<dynamics damping="10" friction="1"/>
<axis xyz="0 1 0"/>
</joint>
这意味着它们能够像旋转关节一样转动,但是它们的转动角具有一定的限制。 <limit>标签用于选择以下属性:effort关节所承受的最大力,lower赋值给关节的下限(旋转接头revolute joint的单位是弧度,带滑移链prismatic joint的单位是米),upper赋值给关节的上限,velocity强制关节的最大速度。
物理和碰撞属性
如果想在Gazebo或者其他仿真软件中进行机器人仿真,就需要添加物理属性和碰撞属性。这意味着我们需要设定几何尺寸来计算可能的碰撞。例如,需要首先设定重量我们才能够计算惯性等。 需要保证模型文件中的所有连接都有这些参数,否则就无法对这些机器人进行仿真。 对于纹理网格模型文件来说,使用简单的几何形状比实际的纹理网格模型更容易进行碰撞计算。相比简单的几何形状,在两个纹理网格模型之间进行碰撞计算要使用更加复杂的计算方法,也会耗费更多的计算资源。
<collision>
<geometry>
<mesh filename="package://urdf_tutorial/meshes/body3.dae" />
</geometry>
</collision>
注意: 对于其他的link也是如此。记住,要为所有link添加collision和inertial元素,因为如果不这样做的话,Gazebo将无法使用这些模型。 当然urdf的升级版为xacro——一种更好的机器人建模方法。
<!--XACRO for intertial -->
<xacro:macro name="cylinder_inertial" params="radius length mass">
<inertial>
<mass value="${mass}" />
<inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
izz="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
iyy="${0.5 * mass * radius * radius}" />
</inertial>
</xacro:macro>
<xacro:macro name="box_inertial" params="mass x y z">
<inertial>
<mass value="${mass}" />
<inertia ixx="${mass*(y*y+z*z)/12}" ixy = "0" ixz = "0" iyy="${mass*(x*x+z*z)/12}" iyz = "0" izz="${mass*(x*x+z*z)/12}" />
</inertial>
</xacro:macro>
<xacro:macro name="box_inertial_default" params="mass">
<inertial>
<mass value="${mass}" />
<inertia ixx="0.000001" ixy = "0" ixz = "0" iyy="0.000001" iyz = "0" izz="0.0000001" />
</inertial>
</xacro:macro>
后续博文再做详细介绍吧。
思考与提升:
- 将ROS1中丰富的URDF模型移植到ROS2中吧^_^