airsim_ros_pkgs#

A ROS wrapper over the AirSim C++ client library.

Before you begin#

The Manual Setup directions below are for manual setup of the AirSimExtensions ROS2 wrapper. If you are running the latest AirSimExtensions docker container, manual setup is unnecessary and you can skip to Running.

Manual Setup#

The below steps are meant were tested on Ubuntu 22.04. If you're running AirSim on Windows, you can use Windows Subsystem for Linux (WSL2) to run the ROS wrapper, see the instructions below. If you're unable or don't prefer to install ROS and related tools on your host Linux due to some issues, you can also try it using Docker, see the steps in Using Docker for ROS wrapper

  • If your default GCC version is not 9 or above (check using gcc --version)

    • Install gcc >= 9.0.0: sudo apt-get install gcc-9 g++-9
    • Verify installation by gcc-9 --version
  • Install ROS Humble

  • Install tf2 sensor and mavros packages: sudo apt-get install ros-humble-tf2-sensor-msgs ros-humble-tf2-geometry-msgs ros-humble-mavros* libyaml-cpp-dev ros-humble-depth-image-proc ros-humble-image-proc
  • If you are working on an Azure VM, install Numpy, libstdc++-12-dev and lark (only host host machine, if you are also running a Docker container):

    sudo apt install libstdc++-12-dev && pip install numpy && pip install lark && pip install catkin_package && pip install empy
  • Install colcon:
    curl -s https://packagecloud.io/install/repositories/dirk-thomas/colcon/script.deb.sh | sudo bash and sudo apt install python3-colcon-common-extensions
    or pip install -U colcon-common-extensions.

Build#

  • Build AirSim
git clone https://github.com/microsoft/AirSimExtensions.git;
cd AirSimExtensions;
./setup.sh;
./build.sh;
  • Make sure that you have setup the environment variables for ROS as mentioned in the installation pages above. Add the source command to your .bashrc for convenience (replace humble with specfic version name) -
echo "source /opt/ros/humble/setup.bash" >> ~/.bashrc
source ~/.bashrc
  • Build ROS package and add the source command to your .bashrc for convenience
cd ros2;
colcon build --cmake-args -DCMAKE_C_COMPILER=gcc-9 --cmake-args -DCMAKE_CXX_COMPILER=g++-9 --cmake-args -DCMAKE_BUILD_TYPE=Debug; 
echo "source <path to airsim>/ros2/install/setup.bash" >> ~/.bashrc
source ~/.bashrc

## Source ROS2 ENV and configure DDS unicast communication between Docker container and host - ros2/setup.sh
source ./setup.sh

Running#

Before running airsim_node.launch, make sure to specify path to a settings.json file. See settings.md for details. (if settings.json file doesn't exist, one will be created automatically at Documents\AirSim on Windows and ~/Documents/AirSim on Linux systems.)

Launch ROS2, wait for AirsimROSWrapper Initialized!.

ros2 launch airsim_ros_pkgs airsim_node.launch.py; 
If launch fails with error Unknown SimMode: , failed to set default vehicle settings, your settings.json is invalid. See settings.md for details.

In a separate terminal window, run source ./setup.sh again. Then you can try the following example tasks:#

List Topics#

ros2 topic list

Simple Takeoff and land example#

ros2 service call /airsim_node/SimpleFlight/takeoff airsim_interfaces/srv/Takeoff wait_on_last_task:\ false
The drone takes off in the simulator.
ros2 service call /airsim_node/SimpleFlight/land airsim_interfaces/srv/Land wait_on_last_task:\ false
The drone lands.

Working with Mesh and Segmentation IDs#

Get the RGB color given a mesh ID

ros2 service call /get_color_from_mesh airsim_interfaces/srv/GetColorFromMeshId "{object_id: 'Road_89'}"
Get the RGB color given a segmentation ID
ros2 service call /get_color_from_seg_id airsim_interfaces/srv/GetColorFromSegId "{segmentation_id: 3}"
Get the mesh name associated with a segmentation ID
ros2 service call /get_mesh_from_seg_id airsim_interfaces/srv/GetMeshIdsFromSegId "{segmentation_id: 0}"
Get the segmentation ID associated with a mesh ID
ros2 service call /get_seg_id_from_mesh airsim_interfaces/srv/GetSegIdFromMeshId "{object_id: 'Road_89'}"
Get the segmentation ID associated with a color
ros2 service call /get_seg_id_from_color airsim_interfaces/srv/GetSegIdFromColor "{r: '0', g: '0', b: '0'}"

Move a Vehicle to a Point#

Drone moves to point specified in MoveToPosition service call

ros2 service call /airsim_node/SimpleFlight/move_to_position airsim_interfaces/srv/MoveToPosition \ "{x: 5.0, y: 10.0, z: -5.0, velocity: 0.5, lookahead: -1.0, adaptive_lookahead: 1.0, wait_on_last_task: true}"

Move a Vehicle along a Path#

Drone moves to point specified in MoveToPosition service call. Drive_train_type field determines if drone needs to be oriented in direction that it is moving. Default is forward only. After each point has been traversed, a message outputs its coordinates and those of the point to which the drone is now flying.

ros2 service call /airsim_node/SimpleFlight/move_on_path airsim_interfaces/srv/MoveOnPath \ "{
  path: [
    {
      header: {
        stamp: {
          sec: 0,
          nanosec: 0
        },
        frame_id: 'map'
      },
      pose: {
        position: {
          x: 1.0,
          y: 0.0,
          z: 0.0
        },
        orientation: {
          x: 0.0,
          y: 0.0,
          z: 0.0,
          w: 1.0
        }
      }
    },
    {
      header: {
        stamp: {
          sec: 0,
          nanosec: 0
        },
        frame_id: 'map'
      },
      pose: {
        position: {
          x: 50.0,
          y: 10.0,
          z: 0.0
        },
        orientation: {
          x: 0.0,
          y: 0.0,
          z: 0.707,
          w: 0.707
        }
      }
    }
  ],
  velocity: 1.5,
  lookahead: 1.0,
  adaptive_lookahead: true,
  wait_on_last_task: false,
  drive_train_type: ForwardOnly
}"

Move a Vehicle along a Path with Feedback (action)#

Drone moves to point specified in MoveToPosition action call. Action feedback can be seen in launch window. Drive_train_type field determines if drone needs to be oriented in direction that it is moving. Default is forward only.

ros2 action send_goal /airsim_node/SimpleFlight/move_on_path airsim_interfaces/action/MoveOnPath \ "{
  "path": [
    {
      "header": {
        "stamp": {
          "sec": 0,
          "nanosec": 0
        },
        "frame_id": "map"
      },
      "pose": {
        "position": {
          "x": 0.0,
          "y": 55.0,
          "z": -5.0
        },
        "orientation": {
          "x": 0.0,
          "y": 0.0,
          "z": 0.0,
          "w": 1.0
        }
      }
    },
    {
      "header": {
        "stamp": {
          "sec": 0,
          "nanosec": 0
        },
        "frame_id": "map"
      },
      "pose": {
        "position": {
          "x": -2.0,
          "y": 60.0,
          "z": -12.0
        },
        "orientation": {
          "x": 0.0,
          "y": 0.0,
          "z": 0.707,
          "w": 0.707
        }
      }
    },
    {
      "header": {
        "stamp": {
          "sec": 0,
          "nanosec": 0
        },
        "frame_id": "map"
      },
      "pose": {
        "position": {
          "x": 0.0,
          "y": 0.0,
          "z": 0.0
        },
        "orientation": {
          "x": 0.0,
          "y": 0.0,
          "z": 0.0,
          "w": 1.0
        }
      }
    }
  ],
  "velocity": 1.5,
  "lookahead": 1.0,
  "adaptive_lookahead": true,
  "wait_on_last_task": true,
  drive_train_type: ForwardOnly
}"

Cancel Action#

Action has to be canceled via command, as ctrl+c causes disconnection from action server. Goal id is created during action send... command

ros2 action cancel <action_name> <goal_id>

Get a Voxel Grid of the environment#

See the voxel grid documentation. This is an example to obtain a 2D voxel grid of a plane of 100 by 100 meters and thickness 0.1 that intersects the environment at a height of 20 meters. This Assumes that the AirSim project is located at home/airsim_user/AirSimNH/.

ros2 service call /airsim_node/SimpleFlight/create_voxel_grid airsim_interfaces/srv/VoxelGrid \
"{position_x: 0.0,position_y: 0.0,position_z: -20.0,ncells_x: 1000,ncells_y: 1000,ncells_z: 1,res: 0.1,output_file: '/home/airsim_user/AirSimNH/voxelgrid.binvox'}"

The service for the segmented voxel grid is /airsim_node/SimpleFlight/create_segmented_voxel_grid

Get an Occupancy Grid of the environment#

This is an example to obtain a 2D occupancy grid of a plane of 1000 by 1000 meters and thickness 1.0 that intersects the environment at a height of 0 meters.

ros2 service call /airsim_node/SimpleFlight/create_occupancy_grid airsim_interfaces/srv/OccupancyGrid "{position_x: 0.0,position_y: 0.0,position_z: 0.0,ncells_x: 1000,ncells_y: 1000, res: 1.0}"

The service for the segmented voxel grid is /airsim_node/SimpleFlight/create_occupancy_grid

Save Occupancy Grid as File#

  1. Run the service to generate the occupancy grid message:
    ros2 service call /airsim_node/SimpleFlight/create_occupancy_grid airsim_interfaces/srv/OccupancyGrid "{position_x: 0.0,position_y: 0.0,position_z: 0.0,ncells_x: 1000,ncells_y: 1000, res: 1.0}"
  2. Save occupancy grid as file:
    ros2 service call /map_saver/save_map nav2_msgs/srv/SaveMap "{map_topic: '/airsim_node/occupancy_grid', map_url: '/home/airsim_user/AirSimExtensions/ros2/maps/my_map', image_format: 'pgm', map_mode: 'trinary', free_thresh: '0.25', occupied_thresh: '0.65'}"

Visualize pointclouds in RVIZ#

Add correct frame id#

  1. Get the frame id from the topic header by running the following command in a terminal:
    ros2 topic echo <topic name>
  2. Launch RVIZ
  3. Click on 'global options' in the upper lefthand corner of RVIZ. A dropdown menu should appear, with 'Fixed Frame' as one of the fields. Click on 'Fixed Frame' then click on the frame id that you found in step 1.

Add topic to RVIZ#

  1. Click the 'Add' button on the bottom left corner of RVIZ.
  2. Find desired pointcloud topic under the 'topics' section of the window that pops up, then click 'okay'. Topic name should end with "/points"
  3. Topic should now be publishing to RVIZ. You may need to rotate the visualization window in order to see the pointcloud.

Using AirSim ROS wrapper#

Run RViz#

ros2 launch airsim_ros_pkgs rviz.launch.py;

Using AirSim ROS wrapper#

The ROS wrapper is composed of two ROS nodes - the first is a wrapper over AirSim's multirotor C++ client library, and the second is a simple PD position controller. Let's look at the ROS API for both nodes:

AirSim ROS Wrapper Node#

Publishers:#

  • /airsim_node/origin_geo_point airsim_ros_pkgs/GPSYaw GPS coordinates corresponding to global NED frame. This is set in the airsim's settings.json file under the OriginGeopoint key.

  • /airsim_node/VEHICLE_NAME/global_gps sensor_msgs/NavSatFix This the current GPS coordinates of the drone in airsim.

  • /airsim_node/VEHICLE_NAME/odom_local_ned nav_msgs/Odometry Odometry in NED frame (default name: odom_local_ned, launch name and frame type are configurable) wrt take-off point.

  • /airsim_node/VEHICLE_NAME/CAMERA_NAME/IMAGE_TYPE/camera_info sensor_msgs/CameraInfo Topic contains height, width, distortion model, distortion parameters, intrinsic camera matrix, rectification matrix, projection matrix, binning values, and ROI coordinates

  • /airsim_node/VEHICLE_NAME/CAMERA_NAME/IMAGE_TYPE sensor_msgs/Image RGB or float image depending on image type requested in settings.json.

  • /tf tf2_msgs/TFMessage

  • /airsim_node/VEHICLE_NAME/altimeter/SENSOR_NAME airsim_ros_pkgs/Altimeter This the current altimeter reading for altitude, pressure, and QNH

  • /airsim_node/VEHICLE_NAME/imu/SENSOR_NAME sensor_msgs::Imu IMU sensor data

  • /airsim_node/VEHICLE_NAME/magnetometer/SENSOR_NAME sensor_msgs::MagneticField Meausrement of magnetic field vector/compass

  • /airsim_node/VEHICLE_NAME/distance/SENSOR_NAME sensor_msgs::Range Meausrement of distance from an active ranger, such as infrared or IR

  • /airsim_node/VEHICLE_NAME/lidar/SENSOR_NAME sensor_msgs::PointCloud2 LIDAR pointcloud

Subscribers:#

Services:#

Parameters:#

  • /airsim_node/world_frame_id [string] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: world_ned Set to "world_enu" to switch to ENU frames automatically

  • /airsim_node/odom_frame_id [string] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: odom_local_ned If you set world_frame_id to "world_enu", the default odom name will instead default to "odom_local_enu"

  • /airsim_node/coordinate_system_enu [boolean] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: false If you set world_frame_id to "world_enu", this setting will instead default to true

  • /airsim_node/update_airsim_control_every_n_sec [double] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: 0.01 seconds. Timer callback frequency for updating drone odom and state from airsim, and sending in control commands. The current RPClib interface to unreal engine maxes out at 50 Hz. Timer callbacks in ROS run at maximum rate possible, so it's best to not touch this parameter.

  • /airsim_node/update_airsim_img_response_every_n_sec [double] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: 0.01 seconds. Timer callback frequency for receiving images from all cameras in airsim. The speed will depend on number of images requested and their resolution. Timer callbacks in ROS run at maximum rate possible, so it's best to not touch this parameter.

  • /airsim_node/publish_clock [double] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: false Will publish the ros /clock topic if set to true.

Simple PID Position Controller Node#

Run#

ros2 launch airsim_ros_pkgs position_controller_simple.launch.py

Parameters:#

  • PD controller parameters:
  • /pd_position_node/kd_x [double], /pd_position_node/kp_y [double], /pd_position_node/kp_z [double], /pd_position_node/kp_yaw [double] Proportional gains

  • /pd_position_node/kd_x [double], /pd_position_node/kd_y [double], /pd_position_node/kd_z [double], /pd_position_node/kd_yaw [double] Derivative gains

  • /pd_position_node/reached_thresh_xyz [double] Threshold euler distance (meters) from current position to setpoint position

  • /pd_position_node/reached_yaw_degrees [double] Threshold yaw distance (degrees) from current position to setpoint position

  • /pd_position_node/update_control_every_n_sec [double] Default: 0.01 seconds

Services:#

  • /airsim_node/VEHICLE_NAME/gps_goal [Request: srv/SetGPSPosition] Target gps position + yaw. In absolute altitude.

  • /airsim_node/VEHICLE_NAME/local_position_goal [Request: srv/SetLocalPosition] Target local position + yaw in global NED frame.

Subscribers:#

  • /airsim_node/origin_geo_point airsim_ros_pkgs/GPSYaw Listens to home geo coordinates published by airsim_node.

  • /airsim_node/VEHICLE_NAME/odom_local_ned nav_msgs/Odometry Listens to odometry published by airsim_node

Publishers:#

Global params#

  • Dynamic constraints. These can be changed in dynamic_constraints.launch:

    • /max_vel_horz_abs [double] Maximum horizontal velocity of the drone (meters/second)

    • /max_vel_vert_abs [double] Maximum vertical velocity of the drone (meters/second)

    • /max_yaw_rate_degree [double] Maximum yaw rate (degrees/second)

Misc#

Using Docker for ROS (in progress)#

A Dockerfile is present in the tools directory. To build the airsim-ros image -

cd tools
docker build -t airsim-ros -f Dockerfile-ROS .

To run on a Linux environment, replace the path of the AirSim folder below -

docker run --rm -it --net=host -v <your-AirSim-folder-path>:/home/testuser/AirSim airsim-ros:latest bash

If you are running Docker on a Windows environment, you will need to set additional flags (see Configuring ROS2 communications on Windows host for full ROS2 Docker for Windows instructions) to enable ROS2 communication between the Docker container and the host:

docker run -e VM_IP=<IP address of VM or WSL container> -e DOCKER_CONTAINER_IP=<host.docker.internal IP> -p 7410:7410/udp -p 7412:7412/udp -p 41451:41451 --gpus=all -v "/tmp/.X11-unix:/tmp/.X11-unix:rw" -e DISPLAY airsim_binary:22.04-cudagl11-x11 bash

The above command mounts the AirSim directory to the home directory inside the container. Any changes you make in the source files from your host will be visible inside the container, which is useful for development and testing. Now follow the steps from Build to compile and run the ROS wrapper.

Setting up the Build Environment on Windows10 using WSL1 or WSL2#

These setup instructions describe how to setup "Bash on Ubuntu on Windows" (aka "Windows Subsystem for Linux").

It involves enabling the built-in Windows Linux environment (WSL) in Windows10, installing a compatible Linux OS image, and finally installing the build environment as if it were a normal Linux system.

Upon completion, you will be able to build and run the ros wrapper as in a native linux machine.

WSL1 vs WSL2#

WSL2 is the latest version of the Windows10 Subsystem for Linux. It is many times faster than WSL1 (if you use the native file system in /home/... rather than Windows mounted folders under /mnt/...) and is therefore much preferred for building the code in terms of speed.

Once installed, you can switch between WSL1 or WSL2 versions as you prefer.

WSL Setup steps#
  1. Follow the instructions here. Check that the ROS version you want to use is supported by the Ubuntu version you want to install.

  2. Congratulations, you now have a working Ubuntu subsystem under Windows, you can now go to Ubuntu 16 / 18 instructions and then How to run Airsim on Windows and ROS wrapper on WSL!

Note

You can run XWindows applications (including SITL) by installing VcXsrv on Windows. To use it find and run XLaunch from the Windows start menu. Select Multiple Windows in first popup, Start no client in second popup, only Clipboard in third popup. Do not select Native Opengl (and if you are not able to connect select Disable access control). You will need to set the DISPLAY variable to point to your display: in WSL it is 127.0.0.1:0, in WSL2 it will be the ip address of the PC's network port and can be set by using the code below. Also in WSL2 you may have to disable the firewall for public networks, or create an exception in order for VcXsrv to communicate with WSL2:

export DISPLAY=$(cat /etc/resolv.conf | grep nameserver | awk '{print $2}'):0

Tip

  • If you add this line to your ~/.bashrc file you won't need to run this command again
  • For code editing you can install VSCode inside WSL.
  • Windows 10 includes "Windows Defender" virus scanner. It will slow down WSL quite a bit. Disabling it greatly improves disk performance but increases your risk to viruses so disable at your own risk. Here is one of many resources/videos that show you how to disable it: How to Disable or Enable Windows Defender on Windows 10
  1. See Configuring ROS2 communications on Windows host for establishing communication between ROS2 node on WSL and ROS2 node on Docker container.
File System Access between WSL and Windows10#

From within WSL, the Windows drives are referenced in the /mnt directory. For example, in order to list documents within your () documents folder:

`ls /mnt/c/'Documents and Settings'/<username>/Documents`
or
`ls /mnt/c/Users/<username>/Documents`

From within Windows, the WSL distribution's files are located at (type in windows Explorer address bar):

\\wsl$\<distribution name> e.g. \\wsl$\Ubuntu-18.04

How to run Airsim on Windows and ROS wrapper on WSL#

For WSL 1 execute: export WSL_HOST_IP=127.0.0.1 and for WSL 2: export WSL_HOST_IP=$(cat /etc/resolv.conf | grep nameserver | awk '{print $2}') Now, as in the running section for linux, execute the following:

source devel/setup.bash
roslaunch airsim_ros_pkgs airsim_node.launch output:=screen host:=$WSL_HOST_IP
roslaunch airsim_ros_pkgs rviz.launch