Skip to content

Latest commit

 

History

History
173 lines (145 loc) · 9.36 KB

settings.md

File metadata and controls

173 lines (145 loc) · 9.36 KB

AirSim Settings

Where are Settings Stored?

Windows: Documents\AirSim Linux: ~/Documents/AirSim

The file is in usual json format. On first startup AirSim would create settings.json file with no settings. To avoid problems, always use ASCII format to save json file.

How to Chose Between Car and Multirotor?

The default is to use multirotor. To use car simple set "SimMode": "Car" like this:

{
  "SettingsVersion": 1.0,
  "SimMode": "Car"
}

To choose multirotor, set "SimMode": "".

Available Settings and Their Defaults

Below are complete list of settings available along with their default values. If any of the settings is missing from json file, then below default value is assumed. Please note that if setting has default value then its actual value may be chosen based on other settings. For example, ViewMode setting will have value "FlyWithMe" for drones and "SpringArmChase" for cars.

WARNING: Do not copy paste all of below in your settings.json. We stronly recommand leaving out any settings that you want to have default values from settings.json. Only copy settings that you want to change from default. Only required element is "SettingsVersion": 1.0.

{
  "DefaultVehicleConfig": "",
  "SimMode": "",
  "ClockType": "",
  "ClockSpeed": "1",
  "LocalHostIp": "127.0.0.1",
  "RecordUIVisible": true,
  "LogMessagesVisible": true,
  "ViewMode": "",
  "UsageScenario": "",
  "RpcEnabled": true,
  "EngineSound": true,
  "PhysicsEngineName": "",
  "EnableCollisionPassthrogh": false,
  "Recording": {
    "RecordOnMove": false,
    "RecordInterval": 0.05
  },
  "CaptureSettings": [
    {
      "ImageType": -1,
      "Width": 256,
      "Height": 144,
      "FOV_Degrees": 90,
      "AutoExposureSpeed": 100,
      "AutoExposureBias": 0,
      "AutoExposureMaxBrightness": 0.64,
      "AutoExposureMinBrightness": 0.03,
      "MotionBlurAmount": 0,
      "TargetGamma": 1.0
    }
  ],
  "SubWindows": [
    {"WindowID": 0, "CameraID": 0, "ImageType": 3, "Visible": false},
    {"WindowID": 1, "CameraID": 0, "ImageType": 5, "Visible": false},
    {"WindowID": 2, "CameraID": 0, "ImageType": 0, "Visible": false}    
  ] 
  "SimpleFlight": {
    "FirmwareName": "SimpleFlight",
    "DefaultVehicleState": "Armed",
    "RC": {
      "RemoteControlID": 0,
      "AllowAPIWhenDisconnected": false,
      "AllowAPIAlways": true
    },
    "ApiServerPort": 41451
  },
  "PX4": {
    "FirmwareName": "PX4",
    "LogViewerHostIp": "127.0.0.1",
    "LogViewerPort": 14388,
    "OffboardCompID": 1,
    "OffboardSysID": 134,
    "QgcHostIp": "127.0.0.1",
    "QgcPort": 14550,
    "SerialBaudRate": 115200,
    "SerialPort": "*",
    "SimCompID": 42,
    "SimSysID": 142,
    "SitlIp": "127.0.0.1",
    "SitlPort": 14556,
    "UdpIp": "127.0.0.1",
    "UdpPort": 14560,
    "UseSerial": true,
    "VehicleCompID": 1,
    "VehicleSysID": 135,
    "ApiServerPort": 41451
  }
}

Image Capture Settings

The CaptureSettings determines how different image types such as scene, depth, disparity, surface normals and segmentation views are rendered. The Width, Height and FOV settings should be self explanatory. The AutoExposureSpeed decides how fast eye adaptation works. We set to generally high value such as 100 to avoid artifacts in image capture. Simplarly we set MotionBlurAmount to 0 by default to avoid artifacts in groung truth images. For explanation of other settings, please see this article.

The ImageType element determines which image type the settings applies to. By default it is -1 which is invalid value and you will get an error if you have haven't changed it to a valid value. The valid values are:

Scene = 0, 
DepthPlanner = 1,
DepthPerspective = 2,
DepthVis = 3, 
DisparityNormalized = 4,
Segmentation = 5,
SurfaceNormals = 6

Note that CaptureSettings element is json array so you can add settings for multiple image types easily.

Changing Flight Controller

The DefaultVehicleConfig decides which config settings will be used for your vehicles. By default we use simple_flight so you don't have to do separate HITL or SITL setups. We also support "PX4" for advanced users.

LocalHostIp Setting

Now when connecting to remote machines you may need to pick a specific ethernet adapter to reach those machines, for example, it might be over ethernet or over wifi, or some other special virtual adapter or a VPN. Your PC may have multiple networks, and those networks might not be allowed to talk to each other, in which case the UDP messages from one network will not get through to the others.

So the LocalHostIp allows you to configure how you are reaching those machines. The default of 127.0.0.1 is not able to reach external machines, this default is only used when everything you are talking to is contained on a single PC.

PX4 and MavLink Related Settings

These settings define the Mavlink SystemId and ComponentId for the Simulator (SimSysID, SimCompID), and for an optional external renderer (ExtRendererSysID, ExtRendererCompID) and the node that allows remote control of the drone from another app this is called the Air Control node (AirControlSysID, AirControlCompID).

If you want the simulator to also talk to your ground control app (like QGroundControl) you can also set the UDP address for that in case you want to run that on a different machine (QgcHostIp,QgcPort).

You can connect the simulator to the LogViewer app, provided in this repo, by setting the UDP address for that (LogViewerHostIp,LogViewerPort).

And for each flying drone added to the simulator there is a named block of additional settings. In the above you see the default name "PX4". You can change this name from the Unreal Editor when you add a new BP_FlyingPawn asset. You will see these properties grouped under the category "MavLink". The mavlink node for this pawn can be remote over UDP or it can be connected to a local serial port. If serial then set UseSerial to true, otherwise set UseSerial to false and set the appropriate bard rate. The default of 115200 works with Pixhawk version 2 over USB.

Other Settings

SimMode

Currently SimMode can be set to "", "Multirotor" or "Car". The empty string value "" means that use the default vehicle which is "Multirotor". This determines which vehicle you would be using.

PhysicsEngineName

For cars, we support only PhysX for now (regardless of value in this setting). For multirotors, we support "FastPhysicsEngine" only.

ViewMode

The ViewMode determines how you will view the vehicle. For multirotors, the default ViewMode is "FlyWithMe" while for cars the default ViewMode is "SpringArmChase".

  • FlyWithMe: Chase the vehicle from behind with 6 degrees of freedom
  • GroundObserver: Chase the vehicle from 6' above the ground but with full freedome in XY plane.
  • Fpv: View the scene from front camera of vehicle
  • Manual: Don't move camera automatically. Use arrow keys and ASWD keys for move camera manually.
  • SpringArmChase: Chase the vehicle with camera mounted on (invisible) arm that is attached to the vehicle via spring (so it has some latency in movement).

EngineSound

To turn off the engine sound use setting "EngineSound": false. Currently this setting applies only to car.

SubWindows

This setting determines what is shown in each of 3 subwindows which are visible when you press 0 key. The WindowsID can be 0 to 2, CameraID is integer identifying camera number on the vehicle. ImageType integer value determines what kind of image gets shown according to ImageType enum. For example, for car vehicles below shows driver view, front bumper view and rear view as scene, depth ans surface normals respectively.

  "SubWindows": [
    {"WindowID": 0, "ImageType": 0, "CameraID": 3, "Visible": true},
    {"WindowID": 1, "ImageType": 3, "CameraID": 0, "Visible": true},
    {"WindowID": 2, "ImageType": 6, "CameraID": 4, "Visible": true}
  ]

Recording

The recording feature allows you to record data such as position, orientation, velocity along with image get recorded in real time at given interval. You can start recording by pressing red Record button on lower right or R key. The data is recorded in Documents\AirSim folder, in a timestamped subfolder for each recording session, as csv file.

  • RecordInterval: specifies minimal interval in seconds between capturing two images.
  • RecordOnMove: specifies that do not record frame if there was vehicle's position or orientation hasn't changed

ClockSpeed

Determines the speed of simulation clock with respect to wall clock. For example, value of 5.0 would mean simulation clock has 5 seconds elapsed when wall clock has 1 second elapsed (i.e. simulation is running faster). The value of 0.1 means that simulation clock is 10X slower than wall clock. The value of 1 means simulation is running in real time. It is important to realize that quality of simuation may decrease as the simulation clock runs faster. You might see artifacts like object moving past obstacles because collison is not detected. However slowing down simulation clock (i.e. values < 1.0) generally improves the quality of simulation.