Skip to content

Commit

Permalink
[sensor/docs] API docs, example in hello_drone.py
Browse files Browse the repository at this point in the history
  • Loading branch information
madratman committed Apr 30, 2019
1 parent a9468e9 commit 2baab3f
Show file tree
Hide file tree
Showing 5 changed files with 131 additions and 66 deletions.
1 change: 0 additions & 1 deletion AirLib/include/api/RpcLibAdapatorsBase.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -636,7 +636,6 @@ class RpcLibAdapatorsBase {
GnssReport gnss;
bool is_valid = false;


MSGPACK_DEFINE_MAP(time_stamp, gnss, is_valid);

GpsData()
Expand Down
2 changes: 1 addition & 1 deletion PythonClient/airsim/types.py
Original file line number Diff line number Diff line change
Expand Up @@ -369,7 +369,7 @@ class BarometerData(MsgpackMixin):
pressure = Vector3r()
qnh = Vector3r()

class Magnetometer(MsgpackMixin):
class MagnetometerData(MsgpackMixin):
time_stamp = np.uint64(0)
magnetic_field_body = Vector3r()
magnetic_field_covariance = 0.0
Expand Down
16 changes: 16 additions & 0 deletions PythonClient/multirotor/hello_drone.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,22 @@
s = pprint.pformat(state)
print("state: %s" % s)

imu_data = client.getImuData()
s = pprint.pformat(imu_data)
print("imu_data: %s" % s)

barometer_data = client.getBarometerData()
s = pprint.pformat(barometer_data)
print("barometer_data: %s" % s)

magnetometer_data = client.getMagnetometerData()
s = pprint.pformat(magnetometer_data)
print("magnetometer_data: %s" % s)

gps_data = client.getGpsData()
s = pprint.pformat(gps_data)
print("gps_data: %s" % s)

airsim.wait_key('Press any key to takeoff')
client.takeoffAsync().join()

Expand Down
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ Cars in AirSim

## What's New

* [Added sensor APIs for Barometer, IMU, GPS, Magnetometer, Distance Sensor](https://microsoft.github.io/AirSim/docs/sensors.md)
* Added support for [docker in ubuntu](https://microsoft.github.io/AirSim/docs/docker_ubuntu)
* Added Weather Effects and [APIs](https://microsoft.github.io/AirSim/docs/apis#weather-apis)
* Added [Time of Day API](https://microsoft.github.io/AirSim/docs/apis#time-of-day-api)
Expand Down
177 changes: 113 additions & 64 deletions docs/sensors.md
Original file line number Diff line number Diff line change
@@ -1,73 +1,82 @@
# Sensors in AirSim

AirSim currently supports the following sensors:
* Camera
* Imu
* Magnetometer
* Gps
* Barometer
* Distance
* Lidar
AirSim currently supports the following sensors.
Each sensor is associated with a integer enum specifying its sensor type.

The cameras are currently configured a bit differently than other sensors. The camera configuration and apis are covered in other documents, e.g., [general settings](settings.md) and [image API](image_apis.md).
* Camera
* Barometer = 1
* Imu = 2
* Gps = 3
* Magnetometer = 4
* Distance Sensor = 5
* Lidar = 6

This document focuses on the configuration of other sensors.
**Note** : Cameras are configured differently than the other sensors and do not have an enum associated with them. Look at [general settings](settings.md) and [image API](image_apis.md) for camera config and API.

## Default sensors

If not sensors are specified in the settings json, the the following sensors are enabled by default based on the simmode.
If no sensors are specified in the `settings json`, the the following sensors are enabled by default based on the sim mode.

### Multirotor
* Imu
* Magnetometer
* Gps
* Barometer

### Car
* Gps

### ComputerVision
* None

Please see 'createDefaultSensorSettings' method in [AirSimSettings.hpp](https://github.com/Microsoft/AirSim/tree/master/AirLib//include/common/)
Behind the scenes, 'createDefaultSensorSettings' method in [AirSimSettings.hpp](https://github.com/Microsoft/AirSim/blob/master/AirLib/include/common/AirSimSettings.hpp) which sets up the above sensors with their default parameters, depending on the sim mode specified in the `settings.json` file.

## Configuration of Default Sensor list
## Configuring the default sensor list

A default sensor list can be configured in settings json.
e.g.,
```
"DefaultSensors": {
"Barometer": {
"SensorType": 1,
"Enabled" : true
},
"Gps": {
"SensorType": 1,
"Enabled" : true
},
"Lidar1": {
"SensorType": 6,
"Enabled" : true,
"NumberOfChannels": 16,
"PointsPerSecond": 10000
},
"Lidar2": {
"SensorType": 6,
"Enabled" : false,
"NumberOfChannels": 4,
"PointsPerSecond": 10000
}
The default sensor list can be configured in settings json:

```JSON
"DefaultSensors": {
"Barometer": {
"SensorType": 1,
"Enabled" : true
},
"Imu": {
"SensorType": 2,
"Enabled" : true
},
"Gps": {
"SensorType": 3,
"Enabled" : true
},
"Magnetometer": {
"SensorType": 4,
"Enabled" : true
},
"Distance": {
"SensorType": 5,
"Enabled" : true
},
"Lidar2": {
"SensorType": 6,
"Enabled" : true,
"NumberOfChannels": 4,
"PointsPerSecond": 10000
}
},
```

## Configuration of vehicle specific sensor settings
## Configuring vehicle-specific sensor list

If a vehicle provides its sensor list, it **must** provide the whole list. Selective add/remove/update of the default sensor list is **NOT** supported.
A vehicle specific sensor list can be specified in the vehicle settings part of the json.
e.g.,

```
"Vehicles": {
"Drone1": {
"VehicleType": "simpleflight",
"VehicleType": "SimpleFlight",
"AutoCreate": true,
...
"Sensors": {
Expand All @@ -92,29 +101,69 @@ e.g.,
}
```

If a vehicle provides its sensor list, it must provide the whole list. Selective add/remove/update of the default sensor list is NOT supported.

## Configuration of sensor settings

### Shared settings
There are two shared settings:
* SensorType
An integer representing the sensor-type [SensorBase.hpp](https://github.com/Microsoft/AirSim/tree/master/AirLib//include/sensors/)
```
enum class SensorType : uint {
Barometer = 1,
Imu = 2,
Gps = 3,
Magnetometer = 4,
Distance = 5,
Lidar = 6
};
```
* Enabled
Boolean

### Sensor specific settings
Each sensor-type has its own set of settings as well. Please see [lidar](lidar.md) for example of Lidar specific settings.

## Sensor APIs
Each sensor-type has its own set of APIs currently. Please see [lidar](lidar.md) for example of Lidar specific APIs.
Each sensor-type has its own set of settings as well.
Please see [lidar](lidar.md) for example of Lidar specific settings.

## Sensor APIs
Go to `hello_drone.py` for example usage, or follow below for the full API.

- Barometer

C++
```cpp
msr::airlib::BarometerBase::Output getBarometerData(const std::string& barometer_name, const std::string& vehicle_name);
```

Python
```python
barometer_data = getBarometerData(barometer_name = "", vehicle_name = "")
```

- IMU

C++
```cpp
msr::airlib::ImuBase::Output getImuData(const std::string& imu_name = "", const std::string& vehicle_name = "");
```

Python
```python
imu_data = getImuData(imu_name = "", vehicle_name = "")
```

- GPS

C++
```cpp
msr::airlib::GpsBase::Output getGpsData(const std::string& gps_name = "", const std::string& vehicle_name = "");
```
Python
```python
gps_data = getGpsData(gps_name = "", vehicle_name = "")
```

- Magnetometer

C++
```cpp
msr::airlib::MagnetometerBase::Output getMagnetometerData(const std::string& magnetometer_name = "", const std::string& vehicle_name = "");
```
Python
```python
magnetometer_data = getMagnetometerData(magnetometer_name = "", vehicle_name = "")
```

- Distance sensor

C++
```cpp
msr::airlib::DistanceBase::Output getDistanceSensorData(const std::string& distance_sensor_name = "", const std::string& vehicle_name = "");
```
Python
```python
distance_sensor_name = getDistanceSensorData(distance_sensor_name = "", vehicle_name = "")
```

- Lidar
See [lidar](lidar.md) for Lidar API.

0 comments on commit 2baab3f

Please sign in to comment.