Skip to content

Latest commit

 

History

History
214 lines (161 loc) · 10.4 KB

airsim_ros_pkgs.md

File metadata and controls

214 lines (161 loc) · 10.4 KB

airsim_ros_pkgs

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

Setup

  • Install gcc >= 8.0.0: sudo apt-get install gcc-8 g++-8
    Verify installation by gcc-8 --version

  • Ubuntu 16.04

    • Install ROS kinetic
    • Install tf2 sensor and mavros packages: sudo apt-get install ros-kinetic-tf2-sensor-msgs ros-kinetic-mavros*
  • Ubuntu 18.04

    • Install ROS melodic
    • Install tf2 sensor and mavros packages: sudo apt-get install ros-melodic-tf2-sensor-msgs ros-melodic-mavros*
  • Install catkin_tools sudo apt-get install python-catkin-tools or pip install catkin_tools

Build

  • Build AirSim
git clone https://github.com/Microsoft/AirSim.git;
cd AirSim;
./setup.sh;
./build.sh;
  • Build ROS package
cd ros;
catkin build; # or catkin_make

If your default GCC isn't 8 or greater (check using gcc --version), then compilation will fail. In that case, use gcc-8 explicitly as follows-

catkin build -DCMAKE_C_COMPILER=gcc-8 -DCMAKE_CXX_COMPILER=g++-8

Running

source devel/setup.bash;
roslaunch airsim_ros_pkgs airsim_node.launch;
roslaunch airsim_ros_pkgs rviz.launch;

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

  • /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

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

Windows Subsytem for Linux on Windows 10

  • WSL setup:

  • Setup for X apps (like RViz, rqt_image_view, terminator) in Windows + WSL

    • Install Xming X Server.
    • 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.
    • Open Ubuntu 16.04 / 18.04 session by typing Ubuntu 16.04 / Ubuntu 18.04 in Windows start menu.
    • Recommended: Install terminator : $ sudo apt-get install terminator.
    • You can open terminator in a new window by entering $ DISPLAY=:0 terminator -u.