ROS自学实践(4):使用GAZEBO进行物理仿真

rviz中的仿真只是视觉上的仿真,不能称得上物理仿真,gazebo是真正意义上的三维物理仿真平台,可以在里面创建环境等相关信息,方便以后的建模和导航。

1.向xacro模型文件中添加惯性矩阵和碰撞属性

(1)惯性矩阵的计算是理论力学中的内容,可以从维基百科可以查到相应的公式进行计算,下面是部分截图。
在这里插入图片描述
在这里插入图片描述
在这里插入图片描述

<xacro:macro name="cylinder_inertial_matrix" params="m r h">
	<inertial>
		<mass value="${m}"/>
		<inertia ixx="${m*(3*r*r+h*h)/12}" ixy="0" ixz="0" iyy="${m*(3*r*r+h*h)/12}" iyz="0" izz="${m*r*r/2}"/>
	</inertial>
</xacro:macro>

<xacro:macro name="retangle_inertial_matrix" params="m d w h">
	<inertial>
		<mass value="${m}"/>
		<inertia ixx="${m*(d*d+h*h)/12}" ixy="0" ixz="0" iyy="${m*(d*d+w*w)/12}" iyz="0" izz="${m*(h*h+w*w)/12}"/>
	</inertial>
</xacro:macro>

(2)碰撞属性应该和机器人的外形有关,因此和visual标签类似
添加轮子碰撞属性

	<collision>
	    <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
	    <geometry>
	    <cylinder length="${wheel_length}" radius="${wheel_radius}"/>
	    </geometry>
	</collision>
	

添加车身的碰撞属性

      <collision>
	<geometry>  
        <box size="${base_length} ${base_width} ${base_height}"/>  
        </geometry>  
        <origin rpy="0 0 0" xyz="0 0 0"/>
      </collision>

添加车头标识块的碰撞属性

	<collision>
	    <origin xyz="0 0 0" rpy="0 0 0"/>
	    <geometry>
	    <box size=".12 .13 .04"/>
	    </geometry>
	</collision>

(3)添加gazebo标签,比如颜色定义,gazebo颜色与rviz颜色不兼容,需重新定义。

<material name="yellow">
	<color rgba="1 0.4 0 1"/>
</material>
<material name="black">
	<color rgba="0 0 0 0.9"/>
</material>
<material name="gray">
	<color rgba="0.75 0.75 0.75 1"/>
</material>
<material name="white">
	<color rgba="1 1 1 1"/>
</material>
<material name="blue">  
        <color rgba="0 0 .8 1"/>  
</material>  

(4)向joint添加传动装置

<transmission name="${prefix}_wheel_joint_trans">
            <type>transmission_interface/SimpleTransmission</type>
            <joint name="${prefix}_rear_drive_joint" >    <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
            </joint>
            <actuator name="${prefix}_wheel_joint_motor">
                <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
                <mechanicalReduction>1</mechanicalReduction>
            </actuator>
        </transmission>

(5)添加gazebo控制器插件

        <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_rear_drive_joint</leftJoint>
                <rightJoint>right_rear_drive_joint</rightJoint>
                <wheelSeparation>0.8</wheelSeparation>
                <wheelDiameter>${2*wheel_radius}</wheelDiameter>
                <broadcastTF>1</broadcastTF>
                <wheelTorque>30</wheelTorque>
                <wheelAcceleration>1.8</wheelAcceleration>
                <commandTopic>cmd_vel</commandTopic>
                <odometryFrame>odom</odometryFrame> 
                <odometryTopic>odom</odometryTopic> 
                <robotBaseFrame>base_link</robotBaseFrame>
            </plugin>
        </gazebo> 

全部的xacro文件如下:
shcRobot2_base_gazebo.xacro,四个轮子都添加transmission模块,前后两个轮子都进行差速完成转向。

<?xml version="1.0"?> 
<robot name="robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI"        value="3.14159"/>
<xacro:property name="base_length" value="1.3"/>
<xacro:property name="base_width"  value="0.8"/>
<xacro:property name="base_height" value="0.2"/>
<xacro:property name="base_mass"   value="10"/>
<xacro:property name="head_mass"   value="0.2"/>

<xacro:property name="wheel_length" value="0.08"/>
<xacro:property name="wheel_radius" value="0.15"/>
<xacro:property name="wheel_mass"   value="1"/>

<xacro:property name="wheel_x_offset"    value="0.4"/>
<xacro:property name="wheel_y_offset"    value="0.375"/>
<xacro:property name="wheel_z_offset"    value="-0.055"/>

<material name="yellow">
	<color rgba="1 0.4 0 1"/>
</material>
<material name="black">
	<color rgba="0 0 0 0.9"/>
</material>
<material name="gray">
	<color rgba="0.75 0.75 0.75 1"/>
</material>
<material name="white">
	<color rgba="1 1 1 1"/>
</material>
<material name="blue">  
        <color rgba="0 0 .8 1"/>  
</material>  

<xacro:macro name="cylinder_inertial_matrix" params="m r h">
	<inertial>
		<mass value="${m}"/>
		<inertia ixx="${m*(3*r*r+h*h)/12}" ixy="0" ixz="0" iyy="${m*(3*r*r+h*h)/12}" iyz="0" izz="${m*r*r/2}"/>
	</inertial>
</xacro:macro>

<xacro:macro name="retangle_inertial_matrix" params="m d w h">
	<inertial>
		<mass value="${m}"/>
		<inertia ixx="${m*(d*d+h*h)/12}" ixy="0" ixz="0" iyy="${m*(d*d+w*w)/12}" iyz="0" izz="${m*(h*h+w*w)/12}"/>
	</inertial>
</xacro:macro>

<xacro:macro name="steer_wheel" params="prefix reflect">

    <link name="${prefix}_front_wheel">
    	<visual>
	    <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
	    <geometry>
		<cylinder length="${wheel_length}" radius="${wheel_radius}"/>
	    </geometry>
	    <material name="black"/>
        </visual>
	<collision>
	    <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
	    <geometry>
	    <cylinder length="${wheel_length}" radius="${wheel_radius}"/>
	    </geometry>
	</collision>
	<cylinder_inertial_matrix m="${wheel_mass}" r="${wheel_radius}" h="${wheel_length}"/>
    </link>

    <joint name="${prefix}_front_steer_joint"  type="revolute">
	<origin xyz="${wheel_x_offset} ${reflect*wheel_y_offset} ${wheel_z_offset}" rpy="0 0 0"/>
	<parent link="base_link"/>
	<child  link="${prefix}_front_wheel"/>
	<axis   xyz="0 1 0"/>
    </joint>
    <gazebo reference="${prefix}_front_wheel">
        <material>Gazebo/Black</material>
    </gazebo>
            <transmission name="${prefix}_wheel_joint_trans">
            <type>transmission_interface/SimpleTransmission</type>
            <joint name="${prefix}_front_steer_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>

<xacro:macro name="drive_wheel" params="prefix reflect">

    <link name="${prefix}_rear_wheel">
    	<visual>
	    <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
	    <geometry>
		<cylinder length="${wheel_length}" radius="${wheel_radius}"/>
	    </geometry>
	    <material name="black"/>
        </visual>
	<collision>
	    <origin xyz="0 0 0" rpy="${M_PI/2} 0 0"/>
	    <geometry>
	    <cylinder length="${wheel_length}" radius="${wheel_radius}"/>
	    </geometry>
	</collision>
	<cylinder_inertial_matrix m="${wheel_mass}" r="${wheel_radius}" h="${wheel_length}"/>
    </link>

    <joint name="${prefix}_rear_drive_joint"  type="continuous">
	<origin xyz="${-1*wheel_x_offset} ${reflect*wheel_y_offset} ${wheel_z_offset}" rpy="0 0 0"/>
	<parent link="base_link"/>
	<child  link="${prefix}_rear_wheel"/>
	<axis   xyz="0 1 0"/>
    </joint>
    <gazebo reference="${prefix}_rear_wheel">
        <material>Gazebo/Black</material>
    </gazebo>

        <transmission name="${prefix}_wheel_joint_trans">
            <type>transmission_interface/SimpleTransmission</type>
            <joint name="${prefix}_rear_drive_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>

<xacro:macro name="robot_base">

    <link name="head">
    	<visual>
	    <origin xyz="0 0 0" rpy="0 0 0"/>
	    <geometry>
		<box size=".12 .13 .04"/>
	    </geometry>
	    <material name="white"/>
        </visual>
	<collision>
	    <origin xyz="0 0 0" rpy="0 0 0"/>
	    <geometry>
	    <box size=".12 .13 .04"/>
	    </geometry>
	</collision>
	<retangle_inertial_matrix m="${head_mass}" d=".12" w=".13" h=".04"/>
    </link>
    <gazebo reference="head">
        <material>Gazebo/White</material>
    </gazebo>
    <joint name="tobox"  type="fixed">
	<origin xyz="0.3 0 0.1" rpy="0 0 0"/>
	<parent link="base_link"/>
	<child  link="head"/>
    </joint>

    <link name="base_link">  
      <visual> 
        <geometry>  
          <box size="${base_length} ${base_width} ${base_height}"/>  
        </geometry>  
        <origin rpy="0 0 0" xyz="0 0 0"/>
        <material name="blue"/>  
      </visual>
      <collision>
	<geometry>  
        <box size="${base_length} ${base_width} ${base_height}"/>  
        </geometry>  
        <origin rpy="0 0 0" xyz="0 0 0"/>
      </collision>
      <retangle_inertial_matrix m="${base_mass}" d="${base_length}" w="${base_width}" h="${base_height}"/>  
    </link>
    
    <gazebo reference="base_link">
	<material>Gazebo/Blue</material>
    </gazebo>

    <steer_wheel prefix="left"  reflect="1"/>
    <steer_wheel prefix="right" reflect="-1"/>
    <drive_wheel prefix="left"  reflect="1"/>
    <drive_wheel prefix="right" reflect="-1"/>

        <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_rear_drive_joint</leftJoint>
                <rightJoint>right_rear_drive_joint</rightJoint>
                <wheelSeparation>0.8</wheelSeparation>
                <wheelDiameter>${2*wheel_radius}</wheelDiameter>
                <broadcastTF>1</broadcastTF>
                <wheelTorque>80</wheelTorque>
                <wheelAcceleration>3</wheelAcceleration>
                <commandTopic>cmd_vel</commandTopic>
                <odometryFrame>odom</odometryFrame> 
                <odometryTopic>odom</odometryTopic> 
                <robotBaseFrame>base_link</robotBaseFrame>
            </plugin>
        </gazebo> 
        <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_front_steer_joint</leftJoint>
                <rightJoint>right_front_steer_joint</rightJoint>
                <wheelSeparation>0.8</wheelSeparation>
                <wheelDiameter>${2*wheel_radius}</wheelDiameter>
                <broadcastTF>1</broadcastTF>
                <wheelTorque>80</wheelTorque>
                <wheelAcceleration>3</wheelAcceleration>
                <commandTopic>cmd_vel</commandTopic>
                <odometryFrame>odom</odometryFrame> 
                <odometryTopic>odom</odometryTopic> 
                <robotBaseFrame>base_link</robotBaseFrame>
            </plugin>
        </gazebo> 
</xacro:macro>
</robot>

shcRobot_xacro_gazebo.xacro

<?xml version="1.0"?>
<robot name="arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
    <xacro:include filename="$(find shcrobot_description)/urdf/xacro/shcRobot2_base_gazebo.xacro"/>
    <robot_base/>
</robot>

2.创建gazebo仿真环境

在launch文件中添加gazebo环境的描述,下面是对整个launch文件的解析。
(1)添加启动gazebo仿真环境

    <!-- 设置launch文件的参数 -->
           <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"/>


	<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)"/>
    </include>

(2)加载机器人模型描述参数

<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find shcrobot_description)/urdf/xacro/shcRobot2_xacro_gazebo.xacro'"/>

(3)运行关节发布节点

	<!--运行joint_state_publisher节点,发布机器人关节状态-->
	<node name = "robot_state_publisher" pkg = "robot_state_publisher" type = "state_publisher">
		<param name="publish_frequency" type="double" value="20.0" />
	</node>
	<!--运行robot_state_publisher节点,发布tf-->

(4)在gazebo中加载机器人模型

    <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
          args="-urdf -model shcrobot -param robot_description"/> 

3.运行launch文件

完整的launch文件

<launch>
	    <!-- 设置launch文件的参数 -->
    <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"/>

	<!--运行gazebo仿真环境-->
	<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)"/>
    	</include>


	<!-- 加载机器人模型描述参数 -->
	<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find shcrobot_description)/urdf/xacro/shcRobot2_xacro_gazebo.xacro'"/>
	<!--运行joint_state_publisher节点,发布机器人关节状态-->
	<node name = "robot_state_publisher" pkg = "robot_state_publisher" type = "state_publisher">
		<param name="publish_frequency" type="double" value="20.0" />
	</node>
	    <!-- 在gazebo中加载机器人模型-->
    <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
          args="-urdf -model shcrobot -param robot_description"/> 
</launch>

在这里插入图片描述

4.创建仿真环境

在这里插入图片描述

  • 5
    点赞
  • 24
    收藏
    觉得还不错? 一键收藏
  • 5
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 5
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值