gazebo仿真

gazebo仿真

gazebo提供了一个当前最先进的物理引擎,还能够创建虚拟的三维环境来模拟机器人的活动。gazebo可以用于测试一些真实世界的性能:机器人的动量和惯性、夹持器和被加持物之间的摩擦力等。

系统配置

gazebo是一个独立的仿真器,可以独立于ROS使用,也可以很好地与ROS结合使用。首先需要安装ROS相关的功能包。

$ sudo apt install ros-noetic-gazebo-*

安装完成后可以从gazebo_ros功能包中运行empty_world.launch文件。

$ roslaunch gazebo_ros empty_world.launch

如果成功的话,可以看到gazebo的GUI和空的模拟环境。

gazebo仿真环境搭建

在gazebo中仿真时需要建立环境模型,可以使用库里的模型,也可以自己绘制搭建环境模型,也可以在亚马逊robotics的github上下载模型。
下面我们介绍搭建自己环境模型的方法。
1.打开gazebo

$ gazebo

看到如下gazebo界面:

2.点击Edit->Building Editor
进入building editor界面后,可以通过添加wall、door等元素,如图所示

3.编辑好building后另保存模型。

4.退出building editor界面,在左侧insert选项卡下,有一些库模型,可以在刚才新建的building里面添加一些元素,如桌子、人、椅子等物品作为障碍物。添加完成后将模型另存为world即可。
这样模型就搭建好了,记住保存路径,后续仿真中需要用到。

注意:gazebo第一次启动时insert选项卡下并没有库模型,通常情况下gazebo会自动下载模型,但有时候需要我们手动下载。运行如下指令:
$ git clone https://github.com/osrf/gazebo_models.git ~/.gazebo/models
如果提示目标目录非空,可以将目标目录下的文件先删除,然后在执行该指令。

URDF文件配置

在URDF文件需要加入对gazebo的说明,包括对关节传动、摩擦系数、激光雷达仿真模型、controller等的定义与说明。
添加内容如下:

  <!--transmission-->
  <transmission name="front_left_wheel_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="front_left_wheel">
      <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
    </joint>
    <actuator name="front_left_motor">
      <mechanicalReduction>14</mechanicalReduction>
    </actuator>
  </transmission>

  <transmission name="front_right_wheel_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="front_right_wheel">
      <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
    </joint>
    <actuator name="front_right_motor">
      <mechanicalReduction>14</mechanicalReduction>
    <actuator>
  </transmission>

  <transmission name="rear_left_wheel_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="rear_left_wheel">
      <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
    </joint>
    <actuator name="rear_left_motor">
      <mechanicalReduction>14</mechanicalReduction>
    </actuator>
  </transmission> 
  
  <transmission name="rear_right_wheel_transmission">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="rear_right_wheel">
      <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
    </joint>
    <actuator name="rear_right_motor">
      <mechanicalReduction>14</mechanicalReduction>
    </actuator>
  </transmission>

  <!--定义摩擦系数-->
  <gazebo reference="front_left_wheel_Link">
    <material>Gazebo/Black<material>
    <mu1>0.5</mu1>
    <mu2>0.5</mu2>
    <kp>1000000.0</kp>
    <kd>1.0</kd>
  </gazebo>

  <gazebo reference="front_right_wheel_Link">
    <material>Gazebo/Black<material>
    <mu1>0.5</mu1>
    <mu2>0.5</mu2>
    <kp>1000000.0</kp>
    <kd>1.0</kd>
  </gazebo>

  <gazebo reference="rear_left_wheel_Link">
    <material>Gazebo/Black<material>
    <mu1>0.5</mu1>
    <mu2>0.5</mu2>
    <kp>1000000.0</kp>
    <kd>1.0</kd>
  </gazebo>

  <gazebo reference="rear_right_wheel_Link">
    <material>Gazebo/Black<material>
    <mu1>0.5</mu1>
    <mu2>0.5</mu2>
    <kp>1000000.0</kp>
    <kd>1.0</kd>
  </gazebo>

  <!--robot_control plugin-->
  <gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
      <robotNamespace>/<robotNamespace>
      <legacyModeNS>true</legacyModeNS>
      <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
    </plugin>
  </gazebo>

  <!--laser-->
  <gazebo reference="laser">
    <material>Gazebo/Black</material>
    <gravity>true</gravity>
    <sensor type="ray" name="head_hokuyo_sensor">
      <pose>0 0 0 0 0</pose>
      <visualize>true</visualize>
      <update_rate>30</update_rate>
      <ray>
        <scan>
          <horizontal>
            <samples>720</samples>
            <resolution>1</resolution>
            <min_angle>-2.007128606</min_angle>
            <max_angle>2.007128606<min_angle>
          </horizontal>
        </scan>
        <range>
          <min>0.10</min>
          <max>10.0</max>
          <resolution>0.01</resolution>
        </range>
        <noise>
          <type>gaussian</type>
          <mean>0.0</mean>
          <stddev>0.01</stddev>
        </noise>
      </ray>
      <plugin name="gazebo_hokuyo_controller" filename="libgazebo_ros_laser.so">
        <robotNamespace>/</robotNamespace>
        <topicName>/scan</topicName>
        <frameName>laser</frameName>
      </plugin>
    </sensor>
  </gazebo>

注意:gazebo相关定义添加在<robot>标签中

launch文件配置

gazebo相关的工作配置好之后,需要启动相关的节点。
新建一个launch/controller.launch文件:

<launch>
    <rosparam file="$(find pf_description)/config/controller.yaml" command="load"/>
    <node name="controller_manager" pkg="controller_manager" type="spawner" args="joint_state_controller mobile_base_controller"/>
</launch>

新建一个launch/gazebo.launch文件:

<launch>
  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name" value="$(find pf_description)/gazebo_model/pf_world.world"/>
    <arg name="paused" value="false"/>
    <arg name="use_sim_time" value="true"/>
    <arg name="gui" value="true"/>
    <arg name="recording" value="false"/>
    <arg name="debug" value="false"/>
  </include>
  <param name="robot_description" textfile="$(find pf_description)/robots/pf_description_gazebo.URDF" />
  <node name="spawn_model" pkg="gazebo_ros" type="spawn_model" args="-urdf -model pf -param robot_description" output="screen" />

  <node 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" />

  <include file="$(find pf_description)/launch/control.launch"/>
</launch>

其中pf_world.world是我们新建的环境模型。可以替换成你想要的任何模型。
新建一个config/controller.yaml文件配置controller:

joint_state_controller:
  type: joint_state_controller/JointStateController
  publish_rate: 25.0

mobile_base_controller:
  type        : "diff_drive_controller/DiffDriveController"
  left_wheel  : ['front_left_wheel', 'rear_left_wheel']
  right_wheel : ['front_right_wheel', 'rear_right_wheel']
  publish_rate: 25.0              # default: 50

  pose_covariance_diagonal : [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
  twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]

  wheel_separation : 0.465  #轮间距
  wheel_radius : 0.0745    #驱动轮半径

  wheel_separation_multiplier: 1.0 # default: 1.0
  wheel_radius_multiplier    : 1.0 # default: 1.0 

  # Velocity commands timeout [s], default 0.5
  cmd_vel_timeout: 0.5

  # Base frame_id
  base_frame_id: base_link
  estimate_velocity_from_position: true
  enable_odom_tf: true
  preserve_turning_radius: true

  # Velocity and acceleration limits
  linear:
    x:
      has_velocity_limits    : true
      max_velocity           : 1.5  # m/s
      min_velocity           : -1.5 # m/s
      has_acceleration_limits: true
      max_acceleration       : 2.0  # m/s^2
      min_acceleration       : -2.0 # m/s^2
      #has_jerk_limits        : true
      #max_jerk               : 5.0  # m/s^3
  angular:
    z:
      has_velocity_limits    : true
      max_velocity           : 3.0  # rad/s
      has_acceleration_limits: true
      max_acceleration       : 3.14  # rad/s^2
      #has_jerk_limits        : true
      #max_jerk               : 2.5  # rad/s^3

运行

上述文件配置好之后,打开一个终端运行如下指令:

$ roslaunch pf_description gazebo.launch

运行结果如图所示:

在终端中查看topic可以看到如下:

$ rostopic list

可以在/mobile_base_controller/cmd_vel上发布速度指令让机器人移动。

$ rostopic pub /mobile_base_controller/cmd_vel geometry_msgs/Twist "linear:
  x: 0.0
  y: 0.0
  z: 0.0
angular:
  x: 0.0
  y: 0.0
  z: 2.0" -r 10