airsim_ros_pkgs

A ROS2 wrapper over the Cosys-AirSim C++ client library. All coordinates and data are in the right-handed coordinate frame of the ROS standard and not in NED except for geo points. The following was tested on Ubuntu 22.04 with ROS2 Iron.

Build

  • Build Cosys-AirSim as per the instructions.

  • Make sure that you have set up the environment variables for ROS. Add the source command to your .bashrc for convenience (replace iron with specific version name) -

echo "source /opt/ros/iron/setup.bash" >> ~/.bashrc
source ~/.bashrc

-- Install dependencies with rosdep, if not already installed -

apt-get install python3-rosdep
sudo rosdep init
rosdep update
rosdep install --from-paths src -y --ignore-src --skip-keys pcl --skip-keys message_runtime --skip-keys message_generation
  • Build ROS package
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release

Running

source install/setup.bash
ros2 launch airsim_ros_pkgs airsim_node.launch.py

Using Cosys-Airsim ROS wrapper

The ROS wrapper is composed of two ROS nodes - the first is a wrapper over Cosys-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:

Cosys-Airsim ROS Wrapper Node

Publishers:

The publishers will be automatically created based on the settings in the settings.json file for all vehicles and the sensors.

  • /airsim_node/VEHICLE-NAME/car_state airsim_interfaces::CarState The state of the car if the vehicle is of this sim-mode type.

  • /airsim_node/VEHICLE-NAME/computervision_state airsim_interfaces::ComputerVisionState The state of the computer vision actor if the vehicle is of this sim-mode type.

  • /airsim_node/origin_geo_point airsim_interfaces::GPSYaw GPS coordinates corresponding to global 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/environment airsim_interfaces::Environment

  • /airsim_node/VEHICLE-NAME/odom_local nav_msgs::Odometry Odometry frame (default name: odom_local, launch name and frame type are configurable) wrt take-off point.

  • /airsim_node/VEHICLE-NAME/CAMERA-NAME_IMAGE-TYPE/camera_info sensor_msgs::CameraInfo Optionally if the image type is annotation the annotation layer name is also included in the topic name.

  • /airsim_node/VEHICLE-NAME/CAMERA-NAME_IMAGE-TYPE/image sensor_msgs::Image RGB or float image depending on image type requested in settings.json. Optionally if the image type is annotation the annotation layer name is also included in the topic name.

  • /tf tf2_msgs::TFMessage

  • /airsim_node/VEHICLE-NAME/altimeter/SENSOR_NAME airsim_interfaces::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 Measurement of magnetic field vector/compass.

  • /airsim_node/VEHICLE-NAME/distance/SENSOR_NAME sensor_msgs::Range Measurement of distance from an active ranger, such as infrared or IR

  • /airsim_node/VEHICLE-NAME/lidar/points/SENSOR_NAME/ sensor_msgs::PointCloud2 LIDAR pointcloud

  • /airsim_node/VEHICLE-NAME/lidar/labels/SENSOR_NAME/ airsim_interfaces::StringArray Custom message type with an array of string that are the labels for each point in the pointcloud of the lidar sensor

  • /airsim_node/VEHICLE-NAME/gpulidar/points/SENSOR_NAME/ sensor_msgs::PointCloud2 GPU LIDAR pointcloud. The instance segmentation/annotation color data is stored in the rgb field of the pointcloud. The intensity data is stored as well in the intensity field

  • /airsim_node/VEHICLE-NAME/echo/active/points/SENSOR_NAME/ sensor_msgs::PointCloud2 Echo sensor pointcloud for active sensing

  • /airsim_node/VEHICLE-NAME/echo/passive/points/SENSOR_NAME/ sensor_msgs::PointCloud2 Echo sensor pointcloud for passive sensing

  • /airsim_node/VEHICLE-NAME/echo/active/labels/SENSOR_NAME/ airsim_interfaces::StringArray Custom message type with an array of string that are the labels for each point in the pointcloud for the active echo pointcloud

  • /airsim_node/VEHICLE-NAME/echo/passive/labels/SENSOR_NAME/ airsim_interfaces::StringArray Custom message type with an array of string that are the labels for each point in the pointcloud for the passive echo pointcloud

  • /airsim_node/instance_segmentation_labels airsim_interfaces::InstanceSegmentationList Custom message type with an array of a custom messages that are the names, color and index of the instance segmentation system for each object in the world.

  • /airsim_node/object_transforms airsim_interfaces::ObjectTransformsList Custom message type with an array of geometry_msgs::TransformStamped that are the transforms of all objects in the world, each child frame ID is the object name.

Subscribers:

Services:

Parameters:

  • /airsim_node/host_ip [string] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: localhost The IP of the machine running the airsim RPC API server.

  • /airsim_node/host_port [string] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: 41451 The port of the machine running the airsim RPC API server.

  • /airsim_node/enable_api_control [string] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: false Set the API control and arm the drones on startup. If not set to true no control is available.

  • /airsim_node/enable_object_transforms_list [string] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: true Retrieve the object transforms list from the airsim API at the start or with the service to refresh. If disabled this is not available but can save time on startup.

  • /airsim_node/host_port [string] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: 41451 The port of the machine running the airsim RPC API server.

  • /airsim_node/is_vulkan [string] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: True If using Vulkan, the image encoding is switched from rgb8 to bgr8.

  • /airsim_node/world_frame_id [string] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: world

  • /airsim_node/odom_frame_id [string] Set in: $(airsim_ros_pkgs)/launch/airsim_node.launch Default: odom_local

  • /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/update_lidar_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 Lidar data in airsim. Timer callbacks in ROS run at maximum rate possible, so it's best to not touch this parameter.

  • /airsim_node/update_gpulidar_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 GPU-Lidar data in airsim. Timer callbacks in ROS run at maximum rate possible, so it's best to not touch this parameter.

  • /airsim_node/update_echo_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 echo sensor data in airsim. 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

Parameters:

  • PD controller parameters:
  • /pd_position_node/kp_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:

Subscribers:

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

  • /airsim_node/VEHICLE-NAME/odom_local 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)