In this repository, we implemented two ground effect models in AirSim, which can be activated through customized high-level C++/Python APIs. In order to use it, you need to substitute the original AirLib folder with the one provided here and rebuild by running ./build.sh
if using Ubuntu (check out more on development workflow for windows here). However, we are also aware that many researchers have already made their own contributions on the source code, and cannot simply replace their AirLib folder with this one. Therefore, we provide details in the sequel on what mathematical models do we choose for ground effect and how we implement them in the source code.
The following equations show a standard formulation of quadrotor kinematics and dynamics.
where
Assumptions:
- All of the rotors face the same direction.
- All of the rotors are the same.
The following equation shows the relation between motor speeds and generalized forces through a mixer matrix.
where
Note: Propeller aerodynamic coefficients used here follow standard definitions as instructed by UIUC Propeller Data Site. Moreover, another important parameter of propeller characteristics is power coefficient which can be formulated as follows:
Ideal thrust is
Actual thrust affected by ground effect is
where
The following two ground effect models are considered here. Cheeseman-Bennett model is a traditional model for helicopters that reveals simple relation between ground effect coefficient
- Cheeseman-Bennett model:
where
- Conyers's parametric model:
where
We start with providing the background of how thrust and torque (wrench) are calculated in AirSim in the original source code.
-
Maximum thrust and torque generated by one single propeller: They are calculated in
RotorParams.hpp
, using thrust and power coefficient. -
Output thrust and torque generated by one single propeller: They are calculated in
RotorActuator.hpp
, based on two parameters:output.control_signal_filtered
(a value between 0 and 1, can be considered as squared value) andair_density_ratio_
(forces and torques are proportional to air density). These outputs will be "stored" inPhysicsBodyVertex.hpp
and read or updated viagetWrench()
andsetWrench()
. The sum of all the forces and torques generated by all the propellers are called "body wrench" inFastPhysicsEngine.hpp
. But notice that body wrench is ONLY one part of the wrench that the multirotor experiences in the environment! -
Actual total wrench: This eventually applies to the drone taking into account the environmental interaction and is calculated within
updatePhysics()
inFastPhysicsEngine.hpp
. Specifically, it is the sum of non-collision wrench and collision response. Furthermore, the non-collision wrench is derived by body wrench and drag wrench.
Data | Value | Source | Note |
---|---|---|---|
Thrust coefficient (C_T) | 0.109919 | RotorParams.hpp |
GWS 9x5 propeller @ 6396.667 RPM. |
Power coefficient (C_P) | 0.040164 | RotorParams.hpp |
GWS 9x5 propeller @ 6396.667 RPM. |
Propeller diameter (D) | 0.2286m | RotorParams.hpp |
|
Quadrotor mass (m) | 1kg | MultiRotorParams.hpp |
|
Propeller spacing (2*l_{arm}) | 0.690m | MultiRotorParams.hpp |
Default value is 0.2275m*2. We modified this number to be aligned with the setup in Conyer’s paper. |
This is to retrieve altitude above the ground data from distance sensor using AirSim APIs.
Note: Distance sensor is specified in settings.json
in the directory of Documents/AirSim
as follows. The position of the sensor is set to be 0.85m below ("Z: 0.85"
) the center of mass of the multirotor. This value (or bias) is calibrated from simulation, taking the average of subtraction between distance sensor measurement and ground truth when Z: 0
.
"DistanceCustom": {
"SensorType": 5,
"Enabled": true,
"MinDistance": 0.1,
"MaxDistance": 40,
"X": 0, "Y": 0, "Z": 0.85,
"Yaw": 0, "Pitch": -90, "Roll": 0,
"DrawDebugPoints": true
},
We assume the ground effect only affects thrust in the vertical axis of the multirotor and there is no influence on either the torques or the forces in horizontal axes. Hence, we have:
-
$T_{IGE}$ is derived from Cheeseman-Bennett or Conyers's parametric model. -
$T_{OGE}$ can be set as the weight of quadrotor with known mass or derived using rotor speeds for more precise results.
Therefore, the increment or reduction is calculated by (
Note: Gravity constant takes value using body.getEnvironment().getState().gravity
from PhysicsBody
class of AirSim with default value of 9.806650 using default settings (including geo-position etc.).
In MultiRotorPhysicsBody.hpp
:
- Include
#include "MultiRotorGroundEffect.hpp"
- Create and instantiate a pointer
MultiRotorGroundEffect* multirotor_ge_;
andmultirotor_ge_ = new MultiRotorGroundEffect;
- Define ground effect function that overrides the virtual one defined in the base class
PhysicsBody.hpp
:virtual real_T getGroundEffect() const override
In FastPhysicsEngine.hpp
:
- Add
getGroundEffect()
intogetNextKinematicsNoCollision()
. Hence the total wrench will be the sum of body wrench, drag wrench, and ground effect, from which the next time step linear acceleration will be derived.
Note: These only provide the idea of how ground effect is implemented into physics engine, and there are some other necessary modifications in the code.
It is found that the parametric ground effect model might not be generic for all possible pairs of drone geometry, and hence numerical instability might occur. To avoid these issues, the following modifications are applied to the parametric model:
- Output thrust ratio is set (in fact must converge) to 1 when
$Z/R > 10$ . - Output thrust ratio is set to 1 (in fact this could go toward infinite but for numerical stability we choose it to be 1 or say, ignore it) when
$Z/R < 0.25$ .
High-level APIs (simSetGroundEffect()
) for multirotor ground effect are implemented in both C++ and Python to facilitate its use for users. Through these APIs, users can turn on the ground effect and choose specific underlying model (i.e., Cheeseman-Bennett or Conyers's parametric model). The implementation follows official document with details as follow:
-
Step 1: Specify ground effect API as vehicle-based API in
VehicleApiBase.hpp
,virtual void simSetGroundEffect(int model) = 0;
and its implementation in
MavLinkMultirotorApi.hpp
,virtual void setGroundEffect(int model) override { ... }
Note that you shall also implement it for other firmwares to avoid compilation errors, i.e.,
ArduCopterApi.hpp
for arducopter,SimpleFlightApi.hpp
for simple_flight,ArduRoverApi.hpp
for ardurover, andPhysXCarApi.hpp
for physxcar. -
Step 2: Add an RPC handler in the server which calls your implemented method in
RpcLibServerBase.cpp
. Vehicle-specific APIs are in their respective vehicle subfolder as mentioned in Step 1.pimpl_->server.bind("simSetGroundEffect", [&](int model, const std::string& vehicle_name) -> void { getVehicleApi(vehicle_name)->simSetGroundEffect(model); });
-
Step 3: Add the C++ client API method in
RpcLibClientBase.cpp
,void RpcLibClientBase::setGroundEffect(int model, const std::string& vehicle_name) { pimpl_->client.call("simSetGroundEffect", model, vehicle_name); }
and
RpcLibClientBase.hpp
,void setGroundEffect(int model, const std::string& vehicle_name);
-
Step 4: Add the Python client API method in
client.py
,def simSetGroundEffect(self, model, vehicle_name = ''): """ Set ground effect characterised by model for multirotor corresponding to vehicle_name Args: model (int): 0 to no ground effect, 1 to Cheeseman-Bennett model, 2 to Parametric model by Stephen Conyers vehicle_name (str, optional): Name of the vehicle to send this command to """ self.client.call('simSetGroundEffect', model, vehicle_name)
A test script in Python is given as follows to validate the above implementation:
###################################################################################
# Description: This script runs the test of multirotor ground effect API in Python.
# Howto:
# - Run this script after taking off the multirotor in the simulator.
# - Press any key to change the underlying ground effect model, you shall see
# messages printed in both UE4 and python terminals specifying the model
# currently under deployment.
# Author: Weibin Gu, Politecnico di Torino @ CSL
# Date: July 29, 2021
###################################################################################
import pprint
import setup_path
import airsim
client = airsim.MultirotorClient()
client.confirmConnection()
client.enableApiControl(True)
GND_EFFECT_MODEL = 0 # 0: no ground effect;
# 1: Cheeseman-Bennett;
# 2: Conyers's parametric (all specified in AirLib)
while(True):
airsim.wait_key('Press any key to change ground effect model')
client.simSetGroundEffect(GND_EFFECT_MODEL)
print(f"Python API: ground effect with model = {GND_EFFECT_MODEL}")
GND_EFFECT_MODEL += 1
if GND_EFFECT_MODEL > 2:
GND_EFFECT_MODEL = 0
Should you have any feedback on this implementation, please feel free to reach out to me via: [email protected]
Last Update: June 30, 2021