From 2baab3fb4229f4a9268f203a212b9eaa0b79e470 Mon Sep 17 00:00:00 2001 From: madratman Date: Mon, 29 Apr 2019 17:53:42 -0700 Subject: [PATCH] [sensor/docs] API docs, example in hello_drone.py --- AirLib/include/api/RpcLibAdapatorsBase.hpp | 1 - PythonClient/airsim/types.py | 2 +- PythonClient/multirotor/hello_drone.py | 16 ++ README.md | 1 + docs/sensors.md | 177 +++++++++++++-------- 5 files changed, 131 insertions(+), 66 deletions(-) diff --git a/AirLib/include/api/RpcLibAdapatorsBase.hpp b/AirLib/include/api/RpcLibAdapatorsBase.hpp index d8c17376e5..ca860d121a 100644 --- a/AirLib/include/api/RpcLibAdapatorsBase.hpp +++ b/AirLib/include/api/RpcLibAdapatorsBase.hpp @@ -636,7 +636,6 @@ class RpcLibAdapatorsBase { GnssReport gnss; bool is_valid = false; - MSGPACK_DEFINE_MAP(time_stamp, gnss, is_valid); GpsData() diff --git a/PythonClient/airsim/types.py b/PythonClient/airsim/types.py index a4490a5fdd..cda3b898e1 100644 --- a/PythonClient/airsim/types.py +++ b/PythonClient/airsim/types.py @@ -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 diff --git a/PythonClient/multirotor/hello_drone.py b/PythonClient/multirotor/hello_drone.py index dec37a25d2..e51556e1c3 100644 --- a/PythonClient/multirotor/hello_drone.py +++ b/PythonClient/multirotor/hello_drone.py @@ -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() diff --git a/README.md b/README.md index 98863f92fb..9ef60001e9 100644 --- a/README.md +++ b/README.md @@ -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) diff --git a/docs/sensors.md b/docs/sensors.md index 6fe40ae209..1c6fbd5879 100644 --- a/docs/sensors.md +++ b/docs/sensors.md @@ -1,65 +1,74 @@ # 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., @@ -67,7 +76,7 @@ e.g., "Vehicles": { "Drone1": { - "VehicleType": "simpleflight", + "VehicleType": "SimpleFlight", "AutoCreate": true, ... "Sensors": { @@ -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.