DJI Tello是一款小型、入门级的无人机,其小巧的机身内却隐藏着强大的功能,它可在实验室中安全飞行,搭载高清摄像头,具备图像追踪、定位等强大功能。此外,它还拥有丰富的API接口,支持ros、python、matlab等多种控制指令,为科研任务提供便利。本文将详细介绍如何利用pybullet搭建tello环境,以进行前期的算法仿真验证。

环境配置

       PyBullet是一个用于物理仿真的Python库,广泛用于机器人学、控制算法开发、虚拟现实等领域。它是Bullet物理引擎的Python封装,提供了强大的工具和接口,使用户能够创建、控制和仿真各种物理系统。本文采用PyBullet作为仿真环境,下面为该环境的setup.py文件,执行安全指令:

pip install e .

setup.py:

setup(
    name='Tello',
    version='0.1',
    author='Spgroc',
    author_email='512429847@qq.com',
    description='A framework to benchmark safety in Reinforcement Learning.',
    long_description=long_description,
    long_description_content_type="text/markdown",
    packages=find_packages(),
    license='',
    url='',
    install_requires=[
        'gym',
        'pybullet>=3.0.6',
        'pillow',
        'matplotlib',
        'pyb_utils',
    ],
    python_requires='>=3.8',
    platforms=['Linux Ubuntu', 'darwin', 'windows'],
    classifiers=[
        'Programming Language :: Python :: 3',
        'Programming Language :: Python :: 3.8',
    ],
)

Tello模型导入

由于官方没有开源3D模型的urdf文件,故需要自己下载模型进行转换,下图为sketchfab免费模型

导入Blender进行处理,根据实际模型大小进行比例缩放,之后导出stl文件:

image-20231123100056330

但由于stl文件点太多,可能会造成仿真软件运行卡顿,故需要进行角点精简

image-20231123100400560

根据Tello参数表,修改urdf文件,添加tello动力学特征

image-20231123102617089

特征参数配置:

<properties arm="0.06" kf="3.16e-10" km="7.94e-12" thrust2weight="2.25" max_speed_kmh="28.2" gnd_eff_coeff="11.36859" prop_radius="4.19e-2" drag_coeff_xy="9.1785e-7" drag_coeff_z="10.311e-7" dw_coeff_1="2267.18" dw_coeff_2=".16" dw_coeff_3="-.11" />

配置可视化及碰撞参数:

 <visual>
      <origin rpy="0 0 55" xyz="0 0 0"/>
      <geometry>
        <mesh filename="./dji_tello.dae" scale=" 1 1 1"/>
      </geometry>
      <material name="orange">
        <color rgba="0.95 0.375 0.375 1.0"/>
      </material>
    </visual>

    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder radius=".06" length=".025"/> 这里把无人机看成一个圆柱形,方便碰撞检测
      </geometry>
    </collision>

image-20231123104324035

根据无人机的尺寸,同时考虑电机直径,四个电机的位置应该为(0.044,0.044,0)(-0.044,0.044,0)(0.044,-0.044,0)(-0.044,-0.044,0)

最终完成tello.urdf文件的配置

<?xml version="1.0" ?>

<robot name="tello">

  <properties arm="0.06" kf="3.16e-10" km="7.94e-12" thrust2weight="2.25" max_speed_kmh="28.2" gnd_eff_coeff="11.36859" prop_radius="4.19e-2" drag_coeff_xy="9.1785e-7" drag_coeff_z="10.311e-7" dw_coeff_1="2267.18" dw_coeff_2=".16" dw_coeff_3="-.11" />
  <link name="base_link"> 

    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="0.087"/>
      <inertia ixx="6.79e-3" ixy="0.0" ixz="0.0" iyy="6.79e-3" iyz="0.0" izz="1.313e-2"/>
    </inertial>

    <!-- links>
      <url="https://ieeexplore.ieee.org/document/9836168" />
    </links -->

    <visual>
      <origin rpy="0 0 55" xyz="0 0 0"/>
      <geometry>
        <mesh filename="./dji_tello.dae" scale=" 1 1 1"/>
      </geometry>
      <material name="orange">
        <color rgba="0.95 0.375 0.375 1.0"/>
      </material>
    </visual>

    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <cylinder radius=".06" length=".0333"/>
      </geometry>
    </collision>

  </link>

  <link name="prop0_link">
    <inertial>
      <origin rpy="0 0 0" xyz="0.044 0.044 0"/>
      <mass value="0"/>
      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
    </inertial>
  </link>
  <joint name="prop0_joint" type="fixed">
    <parent link="base_link"/>
    <child link="prop0_link"/>
  </joint>

  <link name="prop1_link">
    <inertial>
      <origin rpy="0 0 0" xyz="-0.044 0.044 0"/>
      <mass value="0"/>
      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
    </inertial>
  </link>
  <joint name="prop1_joint" type="fixed">
    <parent link="base_link"/>
    <child link="prop1_link"/>
  </joint>

  <link name="prop2_link">
    <inertial>
      <origin rpy="0 0 0" xyz="-0.044 -0.044 0"/>
      <mass value="0"/>
      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
    </inertial>
  </link>
  <joint name="prop2_joint" type="fixed">
    <parent link="base_link"/>
    <child link="prop2_link"/>
  </joint>

  <link name="prop3_link">
    <inertial>
      <origin rpy="0 0 0" xyz="0.044 -0.044 0"/>
      <mass value="0"/>
      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
    </inertial>
  </link>
  <joint name="prop3_joint" type="fixed">
    <parent link="base_link"/>
    <child link="prop3_link"/>
  </joint>

  <link name="center_of_mass_link">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="0"/>
      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
    </inertial>
  </link>
  <joint name="center_of_mass_joint" type="fixed">
    <parent link="base_link"/>
    <child link="center_of_mass_link"/>
  </joint>

</robot>

障碍物模型

长方体障碍物

定义一个长方体,长0.2m,宽0.2m,高1.2m,颜色为紫色,它具有定义的碰撞属性和接触属性,用于在仿真中模拟与其他物体的交互。

image-20231123173837674

<?xml version="0.0" ?>
<robot name="box">
  <link name="base_link">
    <inertial>
      <mass value="5"/>
      <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <geometry>
        <box size="0.2 0.2 1.2"/>
      </geometry>
      <material name="purple">
        <color rgba="0.5 0.15 0.6 1"/>
      </material>
      <origin xyz="0 0 0.6"/>
    </visual>
    <collision>
      <geometry>
        <box size="0.2 0.2 1.2"/>
      </geometry>
      <origin xyz="0 0 0.6"/>
    </collision>
    <contact>
      <lateral_friction value="0.9"/>
      <restitution value="0.4"/>
    </contact>
  </link>
</robot>

房屋框架模型

为了提升任务场景的复杂性,在5m*5m的房间中添加围墙,使得无人机只能通过围墙之间的门才能进行不同区域的穿梭,如图所示,将房屋分成如下四个区域。

image-20231123210849342

<?xml version="0.0" ?>
<robot name="room_5_5">
  <link name="wall_top">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <geometry>
	    <box size="5.1 0.1 1.2"/>
      </geometry>
      <origin xyz="0 2.5 0.6"/>
    </visual>
    <collision>
      <geometry>
	    <box size="5.1 0.1 1.2"/>
      </geometry>
      <origin xyz="0 2.5 0.6"/>
    </collision>
  </link>

  <link name="wall_right">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <geometry>
	    <box size="0.1 5 1.2"/>
      </geometry>
      <origin xyz="2.5 0 0.6"/>
    </visual>
    <collision>
      <geometry>
	    <box size="0.1 5 1.2"/>
      </geometry>
      <origin xyz="2.5 0 0.6"/>
    </collision>
  </link>


  <joint name="top_to_right" type="fixed">
    <origin xyz="0 0 0"/>
    <parent link="wall_top"/>
    <child link="wall_right"/>
  </joint>

    <link name="wall_left">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <geometry>
	    <box size="0.1 5 1.2"/>
      </geometry>
      <origin xyz="-2.5 0 0.6"/>
    </visual>
    <collision>
      <geometry>
	    <box size="0.1 5 1.2"/>
      </geometry>
      <origin xyz="-2.5 0 0.6"/>
    </collision>
  </link>


  <joint name="top_to_left" type="fixed">
    <origin xyz="0.0 0.0 0.0"/>
    <parent link="wall_top"/>
    <child link="wall_left"/>
  </joint>

  <link name="wall_bottom">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <geometry>
	    <box size="5.1 0.1 1.2"/>
      </geometry>
      <origin xyz="0 -2.5 0.6"/>
    </visual>
    <collision>
      <geometry>
	    <box size="5.1 0.1 1.2"/>
      </geometry>
      <origin xyz="0 -2.5 0.6"/>
    </collision>
  </link>

<joint name="right_to_bottom" type="fixed">
    <origin xyz="0.0 0.0 0.0"/>
    <parent link="wall_right"/>
    <child link="wall_bottom"/>
</joint>



  <link name="wall_center_1">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <material name="orange">
        <color rgba="0.86 0.28 0.13 1.0"/>
      </material>
      <geometry>
	    <box size="1.2 0.1 0.4"/>
      </geometry>
      <origin xyz="0 0 0.2"/>
    </visual>
    <collision>
      <geometry>
	    <box size="1.2 0.1 0.4"/>
      </geometry>
      <origin xyz="0 0 0.2"/>
    </collision>
  </link>

<joint name="right_to_center_1" type="fixed">
    <origin xyz="0.0 0.0 0.0"/>
    <parent link="wall_right"/>
    <child link="wall_center_1"/>
</joint>

<link name="wall_center_2">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <material name="orange">
        <color rgba="0.86 0.28 0.13 1.0"/>
      </material>
      <geometry>
	    <box size="0.1 1.2 0.4"/>
      </geometry>
      <origin xyz="0 0 0.2"/>
    </visual>
    <collision>
      <geometry>
	    <box size="0.1 1.2 0.4"/>
      </geometry>
      <origin xyz="0 0 0.2"/>
    </collision>
  </link>

<joint name="top_to_center_2" type="fixed">
    <origin xyz="0.0 0.0 0.0"/>
    <parent link="wall_top"/>
    <child link="wall_center_2"/>
</joint>


<link name="wall_center_3">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <material name="orange">
        <color rgba="0.86 0.28 0.13 1.0"/>
      </material>
      <geometry>
	    <box size="0.1 1.5 0.4"/>
      </geometry>
      <origin xyz="0 1.75 0.2"/>
    </visual>
    <collision>
      <geometry>
	    <box size="0.1 1.5 0.4"/>
      </geometry>
      <origin xyz="0 1.75 0.2"/>
    </collision>
  </link>

<joint name="top_to_center_3" type="fixed">
    <origin xyz="0.0 0.0 0.0"/>
    <parent link="wall_top"/>
    <child link="wall_center_3"/>
</joint>

  <link name="wall_center_4">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <material name="orange">
        <color rgba="0.86 0.28 0.13 1.0"/>
      </material>
      <geometry>
	    <box size="1.5 0.1 0.4"/>
      </geometry>
      <origin xyz="-1.75 0 0.2"/>
    </visual>
    <collision>
      <geometry>
	    <box size="1.5 0.1 0.6"/>
      </geometry>
      <origin xyz="-1.75 0 0.3"/>
    </collision>
  </link>

<joint name="left_to_center_4" type="fixed">
    <origin xyz="0.0 0.0 0.0"/>
    <parent link="wall_left"/>
    <child link="wall_center_4"/>
</joint>


<link name="wall_center_5">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <material name="orange">
        <color rgba="0.86 0.28 0.13 1.0"/>
      </material>
      <geometry>
	    <box size="0.1 1.5 0.4"/>
      </geometry>
      <origin xyz="0 -1.75 0.2"/>
    </visual>
    <collision>
      <geometry>
	    <box size="0.1 1.5 0.4"/>
      </geometry>
      <origin xyz="0 -1.75 0.2"/>
    </collision>
  </link>

<joint name="bottom_to_center_5" type="fixed">
    <origin xyz="0.0 0.0 0.0"/>
    <parent link="wall_bottom"/>
    <child link="wall_center_5"/>
</joint>


  <link name="wall_center_6">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <material name="orange">
        <color rgba="0.86 0.28 0.13 1"/>
      </material>
      <geometry>
	    <box size="1.5 0.1 0.4"/>
      </geometry>
      <origin xyz="1.75 0 0.2"/>
    </visual>
    <collision>
      <geometry>
	    <box size="1.5 0.1 0.4"/>
      </geometry>
      <origin xyz="1.75 0 0.2"/>
    </collision>
  </link>

<joint name="right_to_center_6" type="fixed">
    <origin xyz="0.0 0.0 0.0"/>
    <parent link="wall_right"/>
    <child link="wall_center_6"/>
</joint>


  <link name="wall_up_center_1">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <material name="orange">
        <color rgba="0.86 0.28 0.13 1.0"/>
      </material>
      <geometry>
	    <box size="5 0.1 0.8"/>
      </geometry>
      <origin xyz="0 0 0.8"/>
    </visual>
    <collision>
      <geometry>
	    <box size="5 0.1 0.8"/>
      </geometry>
      <origin xyz="0 0 0.8"/>
    </collision>
  </link>

<joint name="right_to_up_center_1" type="fixed">
    <origin xyz="0.0 0.0 0.0"/>
    <parent link="wall_right"/>
    <child link="wall_up_center_1"/>
</joint>


<link name="wall_up_center_2">
    <inertial>
        <mass value="1"/>
        <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
    </inertial>
    <visual>
      <material name="orange">
        <color rgba="0.86 0.28 0.13 0.2"/>
      </material>
      <geometry>
	    <box size="0.1 5 0.8"/>
      </geometry>
      <origin xyz="0 0 0.8"/>
    </visual>
    <collision>
      <geometry>
	    <box size="0.1 5 0.8"/>
      </geometry>
      <origin xyz="0 0 0.8"/>
    </collision>
  </link>

<joint name="top_to_up_center_2" type="fixed">
    <origin xyz="0.0 0.0 0.0"/>
    <parent link="wall_top"/>
    <child link="wall_up_center_2"/>
</joint>
</robot>

加载模型

使用pybullet加载模型,完成最终的仿真环境效果如图,要求无人机从一个区域到达另一个区域且运动过程中不能与墙壁或障碍物发生碰撞。

image-20231123211411471

import os
import time

import numpy as np
import pybullet as p
import pybullet_data

# Open GUI and set pybullet_data in the path
p.connect(p.GUI)
p.resetDebugVisualizerCamera(3, 90, -30, [0.0, -0.0, -0.0])
p.setTimeStep(1 / 240.)

# Load plane contained in pybullet_data
planeId = p.loadURDF(os.path.join(pybullet_data.getDataPath(), "plane.urdf"))

door1 = p.loadURDF(fileName='Tello/envs/data/obstacles/door.urdf', basePosition=[0.8, 0, 0],
                   baseOrientation=p.getQuaternionFromEuler([0, 0, 0]), useFixedBase=True, globalScaling=0.5)
door2 = p.loadURDF(fileName='Tello/envs/data/obstacles/door.urdf', basePosition=[-0.8, 0, 0],
                   baseOrientation=p.getQuaternionFromEuler([0, 0, 0]), useFixedBase=True, globalScaling=0.5)
door3 = p.loadURDF(fileName='Tello/envs/data/obstacles/door.urdf', basePosition=[0, 0.8, 0],
                   baseOrientation=p.getQuaternionFromEuler([0, 0, np.pi / 2]), useFixedBase=True, globalScaling=0.5)
door4 = p.loadURDF(fileName='Tello/envs/data/obstacles/door.urdf', basePosition=[0, -0.8, 0],
                   baseOrientation=p.getQuaternionFromEuler([0, 0, np.pi / 2]), useFixedBase=True, globalScaling=0.5)
room = p.loadURDF(fileName='Tello/envs/data/obstacles/room_5x5.urdf', basePosition=[0, 0, 0],
                  baseOrientation=p.getQuaternionFromEuler([0, 0, 0]), useFixedBase=True)

obstacle_1 = p.loadURDF(fileName='Tello/envs/data/obstacles/box.urdf', basePosition=[1, -0.5, 0],
                        baseOrientation=p.getQuaternionFromEuler([0, 0, -90]), useFixedBase=True)

robot = p.loadURDF(fileName='Tello/envs/data/robots/tello/tello.urdf', basePosition=[1, -1, 0.2],
                   baseOrientation=p.getQuaternionFromEuler([0, 0, 0]))
# 隐藏调试渲染中的一些控件

# 配置渲染逻辑

p.setRealTimeSimulation(1)
p.configureDebugVisualizer(p.COV_ENABLE_GUI, 0)  # 不显示GUI上的控件
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)  # 打开渲染

p.setGravity(0, 0, -9.8)

while 1:
    p.stepSimulation()
    time.sleep(1. / 240)

在这一篇文章中,我们成功地完成了仿真环境的初步搭建,使用URDF文件描述了机器人及墙壁等环境,并定义了其外观、物理特性以及与环境的交互属性。下一篇文章将集中讨论Tello无人机的飞行控制。