Robot Configuration Settings¶
Project AirSim robots are configured as tree structures of links (physical components with mass and shape) and joints (connections and constraints between links).
The robot can have a physics type associated with it to determine a physics engine that will parse the robot structure and construct a corresponding physics body using the data relevant for that physics type.
The robot can also have a controller that will decide the control outputs to apply to the robot’s actuators.
The array of actuators can be specified with the associated links to apply forces and torques to, based on the control outputs.
An array of sensors can configure various types of sensors such as cameras, IMUs, etc, can be attached to the robot’s links.
Project AirSim currently comes with some base configurations for quadrotor drones to demonstrate how to configure a robot for simulation.
Robot configuration overview (drone example)¶
robot_quadrotor_fastphysics.jsonc
{
"physics-type": "fast-physics",
"links": [...],
"joints": [...],
"controller": {...},
"actuators": [...],
"sensors": [...]
}
Parameter |
Value |
Description |
---|---|---|
|
Physics to use to control the robot’s motion |
|
|
Array of Link settings |
Link settings for each link component of the robot. |
|
Array of Joint settings |
Joint settings for connecting links together. |
|
Controller settings to drive the robot’s actuators. |
|
|
Array of Actuator settings |
Actuator settings for each applying forces and torques to the robot’s links. |
|
Array of Sensor settings |
Sensor settings for attaching sensors to the robot’s links. |
Physics type¶
Non-Physics (Computer Vision mode)¶
"physics-type": "non-physics"
Non-physics mode means that the robot will not move unless its pose is set directly with API calls from the client. This can be useful for “Computer Vision” mode to gather sensor data at manually-specified poses in the simulation world, or if the robot’s motion will be determined by an external algorithm.
Fast Physics¶
"physics-type": "fast-physics"
Fast Physics is a basic light-weight physics model made for aerial drone flight. Fast Physics makes it easy to get started with flying a drone out-of-the-box.
Unreal Physics¶
"physics-type": "unreal-physics"
Unreal physics uses the PhysX engine that’s built-in to Unreal. PhysX can calculate motion for multi-jointed robots with constraints on each joint, as well as rigid body dynamics for aerial drone flight.
Note: The simulation will automatically detect when any actor in the scene is configured to use Unreal Physics, and this will link the physics calculation step to Unreal’s rendering step, so the sim clock setting for step-ns
may need to be much slower (20 ms = ~50 FPS) to maintain reasonable simulation advancement rate.
Link settings¶
A link is a physical component with mass and shape. The link settings consist of inertial, collision, and visual elements.
"links": [
{
"name": "Frame",
"inertial": {...},
"collision": {...},
"visual": {...}
},
...
]
Parameter |
Value |
Description |
---|---|---|
|
string |
Name identifier for the link. |
|
Inertial settings that affect the rigid body motion of the link. |
|
|
Collision settings for collision detection and response. |
|
|
Visual settings for the link’s rendered mesh. |
Inertial settings¶
The link’s inertial settings consist of mass, origin, inertia, and aerodynamic drag.
"inertial": {
"origin": {
"xyz": "0.253 -0.253 -0.01",
"rpy-deg": "0 0 0"
},
"mass": 1.0,
"inertia": {
"type": "geometry",
...
},
"aerodynamics": {
"drag-coefficient": 0.325,
"type": "geometry",
...
}
}
Parameter |
Value |
Description |
---|---|---|
|
string of 3 floats |
Position “X Y Z” of the link relative to the link’s parent joint in meter units. Defaults to all zero if no |
|
string of 3 floats |
Rotation “Roll Pitch Yaw” of the link relative to the link’s parent joint in radian units. Defaults to all zero if no |
|
float |
Mass of this link in SI kg units. |
|
|
Inertia matrix specification type. |
|
float |
The Cd drag coefficient for the link. |
|
|
Aerodynamic drag face specification type. |
Inertia
The link’s rotational inertia matrix (inertia tensor) is specified assuming symmetry around the principle axes so any off-diagonal components (those other than Ixx, Iyy, Izz) are assumed to be zero.
If specified as a matrix
type, directly set the diagonal component values:
"inertia": {
"type": "matrix",
"ixx": 1.0,
"iyy": 1.0,
"izz": 1.0
}
If specified as a geometry
type (only box
is currently supported), set the size
values as “X Y Z” dimensions in SI meter units :
"inertia": {
"type": "geometry",
"geometry": {
"box": {
"size": "0.180 0.110 0.040"
}
}
}
If specified as a point-mass
type, no details are needed because the inertia matrix for this link will be all zero, and the mass will only affect the inertia of other connected links by the Parallel Axis Theorem.
"inertia": {
"type": "point-mass"
}
Aerodynamics
The link’s aerodynamic drag is specified as the drag-coefficient
Cd and cross-sectional face areas on each of the link’s principle axes.
If specified as cross-sectional areas type, directly set the face areas in SI square meter units for the “X Y Z” axes:
"aerodynamics": {
"drag-coefficient": 0.325,
"type": "cross-section-areas-xyz",
"cross-section-areas-xyz": "1.0 1.0 1.0"
}
If specified as a geometry
type (box
or cylinder
are currently supported), then set the geometry’s dimensions and the cross-sectional areas will be calculated automatically.
box
with “X Y Z” dimensions set in SI meter units:
"aerodynamics": {
"drag-coefficient": 0.325,
"type": "geometry",
"geometry": {
"box": {
"size": "0.180 0.110 0.040"
}
}
}
cylinder
with radius
and length
dimensions set in SI meter units:
"aerodynamics": {
"drag-coefficient": 0.325,
"type": "geometry",
"geometry": {
"cylinder": {
"radius": 0.1143,
"length": 0.01
}
}
}
Collision settings¶
The link’s collision settings consist of an enabled flag and parameters for restitution and friction coefficients used in calculating its collision response.
"collision": {
"enabled": true,
"restitution": 0.1,
"friction": 0.5
}
Parameter |
Value |
Description |
---|---|---|
|
bool |
Flag to enable/disable collision detection for this link’s visual mesh. Disabling collision may be useful for non-physics “computer vision” mode while still being able to see the robot’s mesh visually. This defaults to |
|
float |
Restitution coefficient for how the link’s velocity will react normal to the collision (0.0 = no bounce, 1.0 = bounce off with equal velocity as impact). |
|
float |
Friction coefficient for how the link’s velocity will react tangential to the collision (0.0 = no tangential velocity reduction, 1.0 = full tangential velocity reduction). |
Visual settings¶
The link’s visual settings consist of what visual element will be rendered for the link. Currently, only unreal_mesh
geometry types are supported.
The visual
element can be omitted if no visual mesh is desired, such as for non-physics “computer vision” mode, and this will also effectively disable collision detection since there is no mesh to collide with.
"visual": {
"geometry": {
"type": "unreal_mesh",
"name": "/Drone/Quadrotor1",
"scale": "1.0 1.0 1.0"
}
}
Parameter |
Value |
Description |
---|---|---|
|
|
The type of mesh geometry to use (currently only |
|
string |
For |
|
string of 3 floats |
Adjust the mesh’s scale. Defaults to all 1.0 if not specified. Note: A link’s scale will also be inherited by any child links to maintain relative size, so their scales may also need adjustment to compensate. |
Joint settings¶
A joint is a connection between two links (a single parent link and a single child link) in order to define a relationship for relative motion. Constraints for the joint type can specify the type of joint motion to allow.
"joints": [
{
"id": "Frame_Prop_FL",
"type": "fixed",
"parent-link": "Frame",
"child-link": "Prop_FL",
"axis": "0 0 1",
"limit": 1.57,
"damping-constant": 1
},
...
]
Parameter |
Value |
Description |
---|---|---|
|
string |
Name identifier for the joint. |
|
string of 3 floats |
Position “X Y Z” of the joint’s child link relative to the joint’s parent link in meter units. Defaults to all zero if no |
|
string of 3 floats |
Rotation “Roll Pitch Yaw” of the joint’s child link relative to the joint’s parent link in radian units. Defaults to all zero if no |
|
string |
Name identifier for the joint’s parent link. |
|
string |
Name identifier for the joint’s child link. |
|
|
Type of joint constraint. |
|
|
Rotation axis for joint motion. |
|
float |
Rotation angle limit in radians. |
|
float |
Damping coefficient for rotation motion over time. |
Example of fixed joint for drone propellers using Fast Physics which visually rotates the propeller meshes without using joint physics:
"joints": [
{
"id": "Frame_Prop_FL",
"type": "fixed",
"parent-link": "Frame",
"child-link": "Prop_FL",
"axis": "0 0 1"
},
...
]
Example of continuous rotation joint for drone propellers using Unreal Physics which rotates the propeller meshes using some applied torque on the propellers:
"joints": [
{
"id": "Frame_Prop_FL",
"origin": {
"xyz": "0.253 -0.253 -0.01",
"rpy-deg": "0 0 0"
},
"type": "continuous",
"parent-link": "Frame",
"child-link": "Prop_FL",
"axis": "0 0 1",
"damping-constant": 1
},
...
]
Controller settings¶
A controller is used to decide how to command the robot’s actuators in order to apply forces and torques on the robot’s links. Only a single controller per robot is currently supported.
"controller": {
"id": "Simple_Flight_Controller",
"airframe-setup": "quadrotor-x",
"type": "simple-flight-api",
"simple-flight-api-settings": {...}
}
Parameter |
Value |
Description |
---|---|---|
|
string |
Name identifier for the controller. |
|
string |
Type of airframe. Simple Flight currently supports |
|
string |
Type of the controller. Currently, |
|
Settings specific to the |
|
|
See PX4 settings |
Settings specific to the |
|
Settings specific to the |
Simple Flight settings¶
The simple-flight-api-settings
collection contains the settings for the Simple Flight controller:
"simple-flight-api-settings": {
"actuator-order": [
...
]
}
Parameter |
Value |
Description |
---|---|---|
|
Array of actuator |
The actuator name identifiers to link to the controller’s commanded outputs. See Actuator order settings below for the order. |
PX4 settings¶
The px4-settings
collection contains the settings for the PX4 flight controller:
"px4-settings": {
"lock-step" : true,
"use-serial": false,
"serial-port": "*",
"serial-baud-rate": 115200,
"use-tcp": true,
"tcp-port": 4560,
"control-ip-address": "127.0.0.1",
"control-port-local": 14540,
"control-port-remote": 14540, //Used only when control-ip-address is not the local host
"qgc-host-ip": "", //Set only when enabling GCS proxy
"qgc-port": 14550, //Set only when enabling GCS proxy
"parameters": {
"NAV_RCL_ACT": 0,
"NAV_DLL_ACT": 0,
"COM_OBL_ACT": 1,
"LPE_LAT": 47.641468,
"LPE_LON": -122.140165
},
"actuator-order": [
...
]
}
Parameter |
Value |
Description |
---|---|---|
|
bool |
Enables lock-step mode with the PX4 SITL configuration. When true, Project AirSim and PX4 execute synchronously and can run faster or slower than real time as needed. When false, Project AirSim and PX4 execute asynchronously in real time and can lost step with each if either cannot run fast enough. |
|
bool |
When true, Project AirSim connects to a PX4 HITL configuration over a serial port. Takes precedence over |
|
string |
When |
|
integer |
When |
|
bool |
When true, Project AirSim connects to a PX4 SITL simulation over TCP/IP. |
|
integer |
When |
|
integer |
This setting is used when PX4 SITL is running remotely. When |
|
string |
When |
|
string |
When |
|
string |
When |
|
string |
When non-empty, specifies the IP address where Project AirSim will connect to the ground control station (such as QGroundControl). See Ground control station settings, below. |
|
integer |
When |
|
Array of actuator |
The actuator name identifiers to link to the controller’s commanded outputs. See Actuator order settings below for the order. |
PX4 communication port settings¶
In a PX4 HITL configuration, PX4 communicates with Project AirSim over the MAVLink communications channel (either serial or serial over USB). PX4 sends control messages such as actuator settings while Project AirSim sends messages such as sensor data updates.
In a PX4 SITL configuration, PX4 communicates with Project AirSim using two separate communications channels: one for simulator messages (mainly sensor data) and another for API/offboard messages (actuator settings and flight control.) Simulation messages are sent over the TCP/IP port specified by tcp-port
. API/offboard messages are sent over the UDP/IP port specified by control-port
. This enables PX4 to support additional SITL features such as locked-step mode.
When using multiple vehicles in the simulation, each robot has its own external developer/offboard API instance. The first nine Project AirSim robot instances configure control-port
to ports 14590
through 14598
sequentially. The tenth and subsequent instances sets control-port
to port 14599
which is shared. All robots set tcp-port
to the same value.
Project AirSim supports several different PX4 SITL configurations: on the same computer, different computers, and Windows Subsystem for Linux 2 (WSL2.) For more information on these configurations, see Advanced PX4 SITL configurations. The following tables show how to set the communication settings for each configuration.
Settings for SITL simulation communications channel:
SITL Configuration |
|
|
---|---|---|
Same computer |
Usually |
(Unassigned) |
Different computer |
Usually |
IP address of Project AirSim’s network adapter to PX4 host |
PX4 in WSL2 |
Usually |
IP address of Project AirSim’s virtual network adapter to WSL2 |
PX4 connects to Project AirSim at TCP/IP port tcp-port
.
For PX4 in WSL2, the value for local-host-ip
can be found by running the command ipconfig
in a Command Prompt window and looking for IP address under “Ethernet adapter vEthernet (WSL)”.
Settings for SITL API/offboard communications channel:
SITL Configuration |
|
|
|
Notes |
---|---|---|---|---|
Same computer |
Usually |
(Unassigned) |
|
|
Different computer |
(Ignored) |
Usually |
IP address of PX4 host |
Use MAVLink Router running on the PX4 host. |
PX4 in WSL2 |
Usually |
(Unassigned) |
|
In WSL2, set environment variable |
When running PX4 on the same computer or in WSL2, PX4 connects to Project AirSim at UDP/IP port control-port
. When running PX4 remotely, Project AirSim connects to PX4 at the UDP/IP port control-port-remote
.
Ground control station settings¶
On a physical vehicle, PX4 communicates with a GCS (aka. Ground Control Station such as QGroundControl) through a telemetry link (usually via radio). In a PX4 SITL configuration, the PX4 SITL simulation connects directly to the GCS software over the local computer network. In a PX4 HITL configuration, only one application can connect to the PX4 device hardware at a time, so the GCS can’t connect to the PX4 device when it’s connected Project AirSim. Project AirSim, however, can act as a proxy enabling a GCS to be used with the simulation.
When the GCS application is run on the same computer as Project AirSim and PX4, do the following:
PX4 Configuration |
Setup (ground control station on same computer) |
---|---|
HITL |
Project AirSim will proxy the GPC. Set |
SITL |
PX4 will connect to the GCS directly. Leave |
Project AirSim’s GCS proxy also allows the GCS application can be run on a remote computer with both PX4 HITL and SITL configurations:
Set
qgc-host-ip
to the IP address of the computer running the GCS application.Set
qgc-port
to the UDP/IP port of the GCS application (usually14550
.)Remember to configure the network firewall software of Project AirSim’s computer to allow outgoing connections to the GCS’ UDP/IP port and of the GCS computer to allow incoming connections to the same port.
Actuator order settings¶
Under simple-flight-api-settings
and px4-settings
this array maps the control outputs from the controller to the robot’s actuators.
"simple-flight-api-settings": {
"actuator-order": [
{
"id": "Prop_FR_actuator"
},
{
"id": "Prop_RL_actuator"
},
{
"id": "Prop_FL_actuator"
},
{
"id": "Prop_RR_actuator"
}
]
}
Parameter |
Value |
Description |
---|---|---|
|
Array of actuator |
The actuator name identifiers to link to the controller’s commanded outputs. See below for the order. |
The order and number of the actuator id
tags depends on the airframe:
Project AirSim Airframe |
Actuator Order |
---|---|
|
Quadrotor-X order (front right, rear left, front left, rear right) |
|
Hexarotor-X order (front right, rear left, front left, rear right) |
|
*VTOL Quad Tailsitter order (front right, rear left, front left, rear right, unused output port, elevon left, elevon right) |
|
*VTOL Tiltrotor order (rotor outboard left, rotor inboard left, rotor inboard right, rotor outboard right, tilt outboard left, tilt inboard left, tilt inboard right, tilt outboard right, aileron left, aileron right, elevator, rudder) |
*Note: The PX4 documentation does not currently show the correct order.
Manual Controller settings¶
The manual-controller-api-settings
collection contains the settings for the Manual Controller:
"manual-controller-api-settings": {
"actuator-order": [
{
"id": "Prop_FR_actuator",
"initial-value": 0.0
},
{
"id": "Prop_RL_actuator",
"initial-value": 0.0
},
{
"id": "Prop_FL_actuator",
"initial-value": 0.0
},
{
"id": "Prop_RR_actuator",
"initial-value": 0.0
}
]
}
Parameter |
Value |
Description |
---|---|---|
|
Array of actuator |
The actuator name identifiers to link to the controller’s commanded outputs. If omitted, the default |
Actuator settings¶
Actuators are used to apply forces and torques to links based on controller commands, and can be attached to parent links.
"actuators": [
{
"name": "Prop_FL_actuator",
"type": "rotor",
"enabled": true,
"parent-link": "Frame",
"child-link": "Prop_FL",
"origin": {
"xyz": "0.253 -0.253 -0.01",
"rpy-deg": "0 0 0"
},
"rotor-settings": {...}
},
...
]
Parameter |
Value |
Description |
---|---|---|
|
string |
Name identifier for the actuator. |
|
|
Type of actuator. See below. |
|
bool |
Enable or disable the actuator without having to delete the config object. |
|
string |
Name identifier for the actuator’s parent link, which the actuator will apply its forces/torques to. |
|
string |
Name identifier for the actuator’s child link, which is currently only used to visually spin propeller links without using joint physics. |
|
string of 3 floats |
Position “X Y Z” of the actuator’s applied forces/torques relative to the parent link’s origin in meter units. Defaults to all zero if no |
|
string of 3 floats |
Rotation “Roll Pitch Yaw” of the actuator’s applied forces/torques relative to the parent link’s origin in radian units. Defaults to all zero if no |
|
See below |
Settings specific to the lift-draw-control-surface actuator type. |
|
See below |
Settings specific to the rotor actuator type. |
|
See below |
Settings specific to the tilt actuator type. |
Actuator types¶
The supported actuator types are:
Actuator Type |
Description |
---|---|
|
Provides movement for wing-like surfaces such as ailerons and rudders. |
|
An actuator that supplies continuous rotation such as the motor for a propeller. |
|
An actuator that supplies limited rotation such as the motor for a tilting rotor pod. Similar to |
The settings for each actuator type is below.
Lift-drag-control actuator settings:¶
"lift-drag-control-surface-settings": {
"target": "Prop_FL_actuator",
"rotation-rate": 0.524,
"smoothing-tc": 0.5
}
Parameter |
Value |
Description |
---|---|---|
|
float |
Maximum surface rotation from zero (radians.) |
|
float |
Smoothing time constant used in a first-order filter to simulate actuator dynamics (inertia, delay). |
Rotor actuator settings:¶
"rotor-settings": {
"turning-direction": "clock-wise",
"normal-vector": "0.0 0.0 -1.0",
"coeff-of-thrust": 0.109919,
"coeff-of-torque": 0.040164,
"max-rpm": 6396.667,
"propeller-diameter": 0.2286,
"smoothing-tc": 0.005
}
Parameter |
Value |
Description |
---|---|---|
|
|
Rotation direction of the rotor. Clockwise is in the positive right-hand rotation around axis, while counter-clockwise is in the opposite direction. |
|
string of 3 floats |
Normal vector to define the rotation axis of the rotor in NED frame. Currently, only |
|
float |
Propeller’s coefficient of thrust, CT. |
|
float |
Propeller’s coefficient of torque, CP. |
|
float |
Max rotation speed in rotations-per-minute units. |
|
float |
Propeller diameter in meter units, used to calculate the rotor’s max thrust and torque. |
|
float |
Smoothing time constant used in a first-order filter to simulate actuator dynamics (inertia, delay). |
Tilt actuator settings:¶
"tilt-settings": {
"target": "Prop_FL_actuator",
"angle-min": 0.0,
"angle-max": 1.57,
"axis": "0.0 -1.0",
"smoothing-tc": 0.5,
"input-map":{...}
}
Parameter |
Value |
Description |
---|---|---|
|
string of 3 floats |
Normal vector to define the rotation axis of the target actuator in NED frame. |
|
float |
Tilt angle at minimum control input, -1.0 (radians.) |
|
float |
Tilt angle at maximum control input, +1.0 (radians.) |
|
See below |
Settings for mapping the control input. |
|
string |
ID of the target actuator being tilted by this actuator. |
|
float |
Smoothing time constant used in a first-order filter to simulate actuator dynamics (inertia, delay). |
Unlike the lift-drag-control-surface
actuator, the tilt
actuator sets the orientation of the target
actuator in addition to rotating the geometry of the child-link
object to handle situations where the child-link geometry is not the same as that of the target actuator.
Input-map settings¶
"input-map": {
"clamp-input": true,
"clamp-output": true,
"input-min": -1.0,
"input-max": 1.0,
"output-min": -1.0,
"output-max": 1.0,
"scale": 1.0,
}
Parameter |
Value |
Description |
---|---|---|
|
bool |
Whether the input control signal is first clamped to the input range (limited to a value at or between |
|
bool |
Whether the output control signal is clamped to the output range. |
|
float |
Minimum input range value. |
|
float |
Maximum input range value. |
|
float |
Scale factor to apply to normalized input value. |
|
float |
Minimum output range value. |
|
float |
Maximum output range value. |
Different flight controllers and control mixers may define the control signal for a particular actuator differently such as the range of the signal (e.g., [-1, +1] vs. [0, +1]) or polarity (-1 to +1 is clockwise vs. counter-clockwise.) While generally the actuator settings can be chosen to account for many of these differences, some situations may require more manipulation than those settings allow.
The input map setting linearly maps the input control signal sent to the actuator to an output control signal processed by the actuator. By setting the input range and output range, the input from the flight controller is mapped to the range preferred by the actuator. The scale setting magnifies or diminishes the input signal and a negative scale setting inverts the input signal. Finally, the clamp-input
and clamp-output
setting determine whether the input signal is clamped to the input range before processing and whether the output signal is clamped to the output range after processing.
The signal processed by the actuator from the control input signal is calculated by the input map as follows:
input-value = control-input clamped to [input-min, input-max] if clamp-input is true; control-input otherwise
output-value = (input_value - input-min) / (input-max - input-min) * scale * (output-max - output-min) + output_min
actuator-signal = output-value clamped to [output-min, output-max] if clamp-output is true; output-value otherwise
The default settings shown in the JSON example at the top of this section is a 1:1 mapping of the input to the output (no change) with the output signal clamped to the range [-1, +1].
Sensor settings¶
Sensors can be attached to parent links to measure data about the environment from the link’s position or about the link itself.
"sensors": [
{
"id": "DownCamera",
"type": "camera",
"enabled": true,
"parent-link": "Frame",
...
},
...
]
Parameter |
Value |
Description |
---|---|---|
|
string |
Name identifier for the sensor. |
|
|
Type of sensor. |
|
bool |
Enable or disable the sensor without having to delete the config object. |
|
string |
Name identifier for the sensor’s parent link, which the sensor will be attached to. |
For each sensor type’s specific settings, see the sensor pages:
Airspeed Settings
Barometer Settings
GPS Settings
IMU Settings
Magnetometer Settings
Copyright (C) Microsoft Corporation. All rights reserved.