gazebo下如何为px4的仿真环境绘制自己的世界模型

前言:这几天同学在做毕设,是关于四旋翼通过扫描二维码进行定点降落,需要在仿真环境下放置二维码以及给四旋翼加装摄像头,我也正好通过这个机会学习一下。

注意:世界模型和对象模型不一样,对象模型指你的仿真控制对象,比如是四旋翼还是固定翼还是无人车。修改对象模型需要修改对应的sdf文件,我这篇博客指针对世界模型,也就是环境模型!!!


一、如何搭建自己的世界环境

我们打开gazebo,是一个空的世界,在px4的源码下,它提供了几个写好的环境模型:/home/zouxu/src_3/Firmware/Tools/sitl_gazebo/worlds

在这里插入图片描述我们可以发现这些世界模型都是以.world结尾的!!!!所以我们自己在为px4的仿真环境绘制自己的世界模型后,也要以.world结尾的形式保存在这里,

明白上面的之后我们就可以开始了:

1.打开gazebo:

sudo gazebo

2.点击左边的insert插入你需要的模型,比如地面、障碍物等等

3.构建好之后点击保存,保存到/home/zouxu/src_3/Firmware/Tools/sitl_gazebo/worlds里面,命名为myworld.world,注意一定要以.world结尾

4.此时保存好的世界模型还不能直接使用,因为我们构建的世界模型里面没有加入物理特性,因此我们打开写好的empty.world,将里面的physics标签复制过去替代myworld.world里的physics标签。下面就是empty.world里面的physics标签内容:

<physics name='default_physics' default='0' type='ode'>
      <gravity>0 0 -9.8066</gravity>
      <ode>
        <solver>
          <type>quick</type>
          <iters>10</iters>
          <sor>1.3</sor>
          <use_dynamic_moi_rescaling>0</use_dynamic_moi_rescaling>
        </solver>
        <constraints>
          <cfm>0</cfm>
          <erp>0.2</erp>
          <contact_max_correcting_vel>100</contact_max_correcting_vel>
          <contact_surface_layer>0.001</contact_surface_layer>
        </constraints>
      </ode>
      <max_step_size>0.004</max_step_size>
      <real_time_factor>1</real_time_factor>
      <real_time_update_rate>250</real_time_update_rate>
      <magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field>
    </physics>

5.这样就可以用了,我们只需修改launch文件即可,这里比如修改mavros_posix_sitl.launch,里面的内容:

<?xml version="1.0"?>
<launch>
    <!-- MAVROS posix SITL environment launch script -->
    <!-- launches MAVROS, PX4 SITL, Gazebo environment, and spawns vehicle -->
    <!-- vehicle pose -->
    <arg name="x" default="0"/>
    <arg name="y" default="0"/>
    <arg name="z" default="0"/>
    <arg name="R" default="0"/>
    <arg name="P" default="0"/>
    <arg name="Y" default="0"/>
    <!-- vehicle model and world -->
    <arg name="est" default="ekf2"/>
    <arg name="vehicle" default="iris"/>
    <arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/myworld.world"/>
    <arg name="sdf" default="$(find mavlink_sitl_gazebo)/models/$(arg vehicle)/$(arg vehicle).sdf"/>

    <!-- gazebo configs -->
    <arg name="gui" default="true"/>
    <arg name="debug" default="false"/>
    <arg name="verbose" default="false"/>
    <arg name="paused" default="false"/>
    <arg name="respawn_gazebo" default="false"/>
    <!-- MAVROS configs -->
    <arg name="fcu_url" default="udp://:14540@localhost:14557"/>
    <arg name="respawn_mavros" default="false"/>
    <!-- PX4 configs -->
    <arg name="interactive" default="true"/>
    <!-- PX4 SITL and Gazebo -->
    <include file="$(find px4)/launch/posix_sitl.launch">
        <arg name="x" value="$(arg x)"/>
        <arg name="y" value="$(arg y)"/>
        <arg name="z" value="$(arg z)"/>
        <arg name="R" value="$(arg R)"/>
        <arg name="P" value="$(arg P)"/>
        <arg name="Y" value="$(arg Y)"/>
        <arg name="world" value="$(arg world)"/>
        <arg name="vehicle" value="$(arg vehicle)"/>
        <arg name="sdf" value="$(arg sdf)"/>
        <arg name="gui" value="$(arg gui)"/>
        <arg name="interactive" value="$(arg interactive)"/>
        <arg name="debug" value="$(arg debug)"/>
        <arg name="verbose" value="$(arg verbose)"/>
        <arg name="paused" value="$(arg paused)"/>
        <arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
    </include>
    <!-- MAVROS -->
    <include file="$(find mavros)/launch/px4.launch">
        <!-- GCS link is provided by SITL -->
        <arg name="gcs_url" value=""/>
        <arg name="fcu_url" value="$(arg fcu_url)"/>
        <arg name="respawn_mavros" value="$(arg respawn_mavros)"/>
    </include>
</launch>

我们需要将里面的<arg name="world" default="$(find mavlink_sitl_gazebo)/worlds/myworld.world"/>标签内容改为我们写的世界的名称即可。

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章