< >
Home » PX4与仿真入门教程 » PX4与仿真入门教程-dronedoc-添加新模型

PX4与仿真入门教程-dronedoc-添加新模型

PX4与仿真入门教程-dronedoc-添加新模型

说明:

  • 介绍使用 2D 激光雷达创建 Iris 模型

步骤:

  • 创建一个目录 iris_2d_lidar 来存储 Iris 模型
cd ~/dronedoc_ws/src/px4_sim_pkg
mkdir -p models/iris_2d_lidar
  • 创建 SDF 文件
  • Gazebo 使用一种称为 SDF 的格式来定义机器人模型
  • SDF和URDF的关系参见说明
  • 想在 Gazebo 中使用 URDF,参考教程
  • 创建一个 model.sdf 文件。这是定义机器人物理模型和形状的文件
  • SDF 允许您包含和重用现有模型
  • 通过编写以下内容来包含现有模型
<include>
  <uri>model://iris</uri>
</include>
  • 我们将使用来自 PX4 Firmware 的 iris 模型
  • 以这种方式包含时GAZEBO_MODEL_PATH,必须设置要用于的模型的路径
  • 如果已经按照本教程搭建了环境,那么模型路径应该已经设置好了
export GAZEBO_MODEL_PATH=$HOME/src/Firmware/Tools/sitl_gazebo/models:$GAZEBO_MODEL_PATH
  • 创建在model.sdf文件
vim models/iris_2d_lidar/model.sdf
  • 内容如下:
<?xml version='1.0'?>
<sdf version='1.6'>
  <model name='iris_2d_lidar'>

    <include>
      <uri>model://iris</uri>
    </include>

    <link name="lidar_link">
      <pose>0 0 0.05 0 -0.0085 0</pose>

      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>0.01</mass>
        <inertia>
          <ixx>2.1733e-6</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>2.1733e-6</iyy>
          <iyz>0</iyz>
          <izz>1.8e-7</izz>
        </inertia>
      </inertial>

      <visual name="lidar_visual">
        <geometry>
          <cylinder>
            <radius>0.01</radius>
            <length>0.05</length>
          </cylinder>
        </geometry>
        <material>
          <script>
            <name>Gazebo/DarkGrey</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>

      <sensor name="laser" type="ray">
        <pose>0 0 0.02 0 0 0</pose>
        <ray>
          <scan>
            <horizontal>
              <samples>720</samples>
              <resolution>1</resolution>
              <min_angle>-2.0944</min_angle>
              <max_angle>2.0944</max_angle>
            </horizontal>
          </scan>
          <range>
            <min>0.1</min>
            <max>15</max>
            <resolution>0.01</resolution>
          </range>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.01</stddev>
          </noise>
        </ray>
        <plugin name="LaserPlugin" filename="libgazebo_ros_laser.so">
            <topicName>/laser/scan</topicName>
            <frameName>/lidar_link</frameName>
          </plugin>
        <always_on>1</always_on>
        <update_rate>40</update_rate>
        <visualize>true</visualize>
      </sensor>
    </link>

    <joint name="lidar_joint" type="fixed">
      <child>lidar_link</child>
      <parent>iris::base_link</parent>
    </joint>

  </model>
</sdf>
  • 创建在model.config文件
vim models/iris_2d_lidar/model.config
  • 内容如下:
<?xml version="1.0"?>
<model>
  <name>iris_2d_lidar</name>
  <version>1.0</version>
  <sdf>model.sdf</sdf>

  <author>
   <name>Takaki Ueno</name>
   <email>t_ueno@eis.hokudai.ac.jp</email>
  </author>

  <description>
    Iris with 2d horizontal lidar.
  </description>
</model>
  • 增加模型路径到gazebo的模拟路径变量里
cd ~/tools/dronedoc/
vim load_environment.sh
  • 添加
export  GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:~/dronedoc_ws/src/px4_sim_pkg/models  

测试:

  • 运行gazebo
cd ~/tools/dronedoc/
source load_environment.sh
gazebo
  • 效果如下:

请输入图片描述

  • 插入模型,效果如下:

请输入图片描述

  • 可以通过posix_sitl.launch指定模型运行
cd ~/tools/dronedoc/
source load_environment.sh
roslaunch px4 posix_sitl.launch sdf:=$HOME/dronedoc_ws/src/px4_sim_pkg/models/iris_2d_lidar/model.sdf
  • 可以通过mavros_posix_sitl.launch指定模型运行
cd ~/tools/dronedoc/
source  load_environment.sh
roslaunch px4 mavros_posix_sitl.launch sdf:=$HOME/dronedoc_ws/src/px4_sim_pkg/models/iris_2d_lidar/model.sdf

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: px4与仿真入门教程