Skip to content

Commit

Permalink
doc fixes to include requestControl, python scripts now does takeoff
Browse files Browse the repository at this point in the history
  • Loading branch information
sytelus committed Sep 3, 2017
1 parent d4b5eed commit af36358
Show file tree
Hide file tree
Showing 7 changed files with 25 additions and 4 deletions.
4 changes: 4 additions & 0 deletions PythonClient/box.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,10 @@
import time

client = AirSimClient('127.0.0.1')
client.confirmConnection()
client.enableApiControl(True)
client.armDisarm(True)
client.takeoff()

print("Flying a small square box using moveByVelocityZ")
print("Try pressing 't' in the AirSim view to see a pink trace of the flight")
Expand Down
1 change: 1 addition & 0 deletions PythonClient/camera.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ def printUsage():
client.confirmConnection()
client.enableApiControl(True)
client.armDisarm(True)
client.takeoff()

help = False

Expand Down
1 change: 1 addition & 0 deletions PythonClient/navigate.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
client.confirmConnection()
client.enableApiControl(True)
client.armDisarm(True)
client.takeoff()

# you must first press "1" in the AirSim view to turn on the depth capture

Expand Down
1 change: 1 addition & 0 deletions PythonClient/path.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
client.confirmConnection()
client.enableApiControl(True)
client.armDisarm(True)
client.takeoff()

# AirSim uses NED coordinates so negative axis is up.
# z of -5 is 5 meters above the original launch point.
Expand Down
3 changes: 3 additions & 0 deletions docs/custom_drone.md
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@ orbit 10 2
This will arm the drone, takeoff ot 5 meters, then do an orbit pattern radius 10 meters, at 2 m/s.
Type '?' to find all available commands.

**Note:** Some commands (for example, `orbit`) are named differently and have different syntax in MavLinkTest and DroneShell (for example, `circlebypath -radius 10 -velocity 21`).

When you land the drone you can stop MavLinkTest and copy the *.mavlink log file that was generated.

# DroneServer and DroneShell
Expand All @@ -50,6 +52,7 @@ DroneShell
Microsoft Research (c) 2016.
Waiting for drone to report a valid GPS location...
==||=> requestcontrol
==||=> arm
==||=> takeoff
==||=> circlebypath -radius 10 -velocity 2
Expand Down
2 changes: 0 additions & 2 deletions docs/px4_sitl.md
Original file line number Diff line number Diff line change
Expand Up @@ -91,5 +91,3 @@ set the LocalIpAddress to the address of your host machine running the Unreal e
There are several options for flying the simulated drone using a remote control or joystick like xbox gamepad. See [remote controllers](remote_control.md#RC_Setup_for_PX4)
17 changes: 15 additions & 2 deletions docs/settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ The file is in usual [json format](https://en.wikipedia.org/wiki/JSON). On first
## 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.

** You do not need to copy below in your settings.json. ** In fact, we stronly recommand leaving out any settings that you want with default values from settings.json.
**WARNING:** Do not copy 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.

````
{
Expand Down Expand Up @@ -81,7 +81,20 @@ Below are complete list of settings available along with their default values. I
````

## Image Capture Settings
The `SceneCaptureSettings`, `DepthCaptureSettings` and `SegCaptureSettings` determines how scene view, depth view and segmentation views are captures. 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](https://docs.unrealengine.com/latest/INT/Engine/Rendering/PostProcessEffects/AutomaticExposure/).
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](https://docs.unrealengine.com/latest/INT/Engine/Rendering/PostProcessEffects/AutomaticExposure/).

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,
DepthMeters = 1,
DepthVis = 2,
DisparityNormalized = 3,
Segmentation = 4,
SurfaceNormals = 5
```

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](simple_flight.md) so you don't have to do separate HITL or SITL setups. We also support ["PX4"](px4_setup.md) for advanced users.
Expand Down

0 comments on commit af36358

Please sign in to comment.