Skip to content

Commit

Permalink
[ros] fix lidar tf, added docs and examples
Browse files Browse the repository at this point in the history
  • Loading branch information
madratman committed May 13, 2019
1 parent 40fb8e1 commit 5e0864c
Show file tree
Hide file tree
Showing 8 changed files with 374 additions and 34 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ Cars in AirSim
[![AirSim Car Demo Video](docs/images/car_demo_video.png)](https://youtu.be/gnz1X3UNM5Y)

## What's New

* A ROS wrapper for multirotors is available. See [airsim_ros_pkgs](https://github.com/microsoft/AirSim/blob/master/ros/src/airsim_ros_pkgs) for the ROS API, and [airsim_tutorial_pkgs](https://github.com/microsoft/AirSim/blob/master/ros/src/airsim_tutorial_pkgs) for tutorials.
* [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)
Expand Down
44 changes: 19 additions & 25 deletions ros/src/airsim_ros_pkgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -37,50 +37,43 @@ Let's look at the ROS API for both nodes:

### AirSim ROS Wrapper Node
#### Publishers:
- `/airsim_node/home_geo_point` [airsim_ros_pkgs/GPSYaw](msg/GPSYaw.msg)
GPS coordinates corresponding to home/spawn point of the drone. These are set in the airsim's settings.json file under the `OriginGeopoint` key. Please see `settings.json`'s [documentation](https://microsoft.github.io/AirSim/docs/settings/).

- `/airsim_node/origin_geo_point` [airsim_ros_pkgs/GPSYaw](msg/GPSYaw.msg)
GPS coordinates corresponding to global NED frame. This is set in the airsim's [settings.json](https://microsoft.github.io/AirSim/docs/settings/) file under the `OriginGeopoint` key.

- `/airsim_node/global_gps` [sensor_msgs/NavSatFix](https://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html)
- `/airsim_node/VEHICLE_NAME/global_gps` [sensor_msgs/NavSatFix](https://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html)
This the current GPS coordinates of the drone in airsim.

- `/airsim_node/odom_local_ned` [nav_msgs/Odometry](https://docs.ros.org/api/nav_msgs/html/msg/Odometry.html)
- `/airsim_node/VEHICLE_NAME/odom_local_ned` [nav_msgs/Odometry](https://docs.ros.org/api/nav_msgs/html/msg/Odometry.html)
Odometry in NED frame wrt take-off point.

- `/airsim_node/vehicle_state` [mavros_msgs/State](https://docs.ros.org/api/mavros_msgs/html/msg/State.html)
Currently, the drone is always `armed`. Hence, there is only one state.

- `/CAMERA_NAME/IMAGE_TYPE/camera_info` [sensor_msgs/CameraInfo](https://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html)
- `/airsim_node/VEHICLE_NAME/CAMERA_NAME/IMAGE_TYPE/camera_info` [sensor_msgs/CameraInfo](https://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html)

- `/CAMERA_NAME/IMAGE_TYPE` [sensor_msgs/Image](https://docs.ros.org/api/sensor_msgs/html/msg/Image.html)
- `/airsim_node/VEHICLE_NAME/CAMERA_NAME/IMAGE_TYPE` [sensor_msgs/Image](https://docs.ros.org/api/sensor_msgs/html/msg/Image.html)
RGB or float image depending on image type requested in settings.json.

- `/tf` [tf2_msgs/TFMessage](https://docs.ros.org/api/tf2_msgs/html/msg/TFMessage.html)


#### Subscribers:
- `/vel_cmd_body_frame` [airsim_ros_pkgs/VelCmd](msg/VelCmd.msg)
- `/airsim_node/vel_cmd_body_frame` [airsim_ros_pkgs/VelCmd](msg/VelCmd.msg)
Ignore `vehicle_name` field, leave it to blank. We will use `vehicle_name` in future for multiple drones.

- `/vel_cmd_world_frame` [airsim_ros_pkgs/VelCmd](msg/VelCmd.msg)
- `/airsim_node/vel_cmd_world_frame` [airsim_ros_pkgs/VelCmd](msg/VelCmd.msg)
Ignore `vehicle_name` field, leave it to blank. We will use `vehicle_name` in future for multiple drones.

- `/gimbal_angle_euler_cmd` [airsim_ros_pkgs/GimbalAngleEulerCmd](msg/GimbalAngleEulerCmd.msg)
Gimbal set point in euler angles.
Use `front_center`, `front_right`, or `front_left` as `camera_name` parameter in the message field.
Ignore `vehicle_name`.

- `/gimbal_angle_quat_cmd` [airsim_ros_pkgs/GimbalAngleQuatCmd](msg/GimbalAngleQuatCmd.msg)
Gimbal set point in quaternion.
Use `front_center`, `front_right`, or `front_left` as `camera_name` parameter in the message field.
Ignore `vehicle_name`.

#### Services:
- `/airsim_node/land` [std_srvs/Empty](https://docs.ros.org/api/std_srvs/html/srv/Empty.html)
- `/airsim_node/VEHICLE_NAME/land` [airsim_ros_pkgs/Takeoff](https://docs.ros.org/api/std_srvs/html/srv/Empty.html)

- `/airsim_node/reset` [std_srvs/Empty](https://docs.ros.org/api/std_srvs/html/srv/Empty.html)
- `/airsim_node/takeoff` [airsim_ros_pkgs/Takeoff](https://docs.ros.org/api/std_srvs/html/srv/Empty.html)

- `/airsim_node/takeoff` [std_srvs/Empty](https://docs.ros.org/api/std_srvs/html/srv/Empty.html)
- `/airsim_node/reset` [airsim_ros_pkgs/Reset](https://docs.ros.org/api/std_srvs/html/srv/Empty.html)
Resets *all* drones

#### Parameters:
- `/airsim_node/update_airsim_control_every_n_sec` [double]
Expand Down Expand Up @@ -123,18 +116,18 @@ Odometry in NED frame wrt take-off point.
Default: 0.01 seconds

#### Services:
- `/airsim_node/gps_goal` [Request: [msgs/airsim_ros_pkgs/GPSYaw](msgs/airsim_ros_pkgs/GPSYaw)]
- `/airsim_node/VEHICLE_NAME/gps_goal` [Request: [msgs/airsim_ros_pkgs/GPSYaw](msgs/airsim_ros_pkgs/GPSYaw)]
Target gps position + yaw.
In **absolute** altitude.

- `/airsim_node/local_position_goal` [Request: [msgs/airsim_ros_pkgs/XYZYaw](msgs/airsim_ros_pkgs/XYZYaw)
Target local position + yaw in NED frame.
- `/airsim_node/VEHICLE_NAME/local_position_goal` [Request: [msgs/airsim_ros_pkgs/XYZYaw](msgs/airsim_ros_pkgs/XYZYaw)
Target local position + yaw in global NED frame.

#### Subscribers:
- `/airsim_node/home_geo_point` [airsim_ros_pkgs/GPSYaw](msg/GPSYaw.msg)
- `/airsim_node/origin_geo_point` [airsim_ros_pkgs/GPSYaw](msg/GPSYaw.msg)
Listens to home geo coordinates published by `airsim_node`.

- `/airsim_node/odom_local_ned` [nav_msgs/Odometry](https://docs.ros.org/api/nav_msgs/html/msg/Odometry.html)
- `/airsim_node/VEHICLE_NAME/odom_local_ned` [nav_msgs/Odometry](https://docs.ros.org/api/nav_msgs/html/msg/Odometry.html)
Listens to odometry published by `airsim_node`

#### Publishers:
Expand All @@ -152,6 +145,7 @@ Odometry in NED frame wrt take-off point.
* `/max_yaw_rate_degree` [double]
Maximum yaw rate (degrees/second)

### Misc
#### Windows Subsytem for Linux on Windows 10
- WSL setup:
* Get [Windows Subsystem for Linux](https://docs.microsoft.com/en-us/windows/wsl/install-win10)
Expand All @@ -165,4 +159,4 @@ Odometry in NED frame wrt take-off point.
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](http://www.ubuntugeek.com/terminator-multiple-gnome-terminals-in-one-window.html) : `$ sudo apt-get install terminator.`
- You can open terminator in a new window by entering `$ DISPLAY=:0 terminator -u`.
- You can open terminator in a new window by entering `$ DISPLAY=:0 terminator -u`.
3 changes: 2 additions & 1 deletion ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json()
// subscribe to control commands on global nodehandle
gimbal_angle_quat_cmd_sub_ = nh_private_.subscribe("gimbal_angle_quat_cmd", 50, &AirsimROSWrapper::gimbal_angle_quat_cmd_cb, this);
gimbal_angle_euler_cmd_sub_ = nh_private_.subscribe("gimbal_angle_euler_cmd", 50, &AirsimROSWrapper::gimbal_angle_euler_cmd_cb, this);
origin_geo_point_pub_ = nh_private_.advertise<airsim_ros_pkgs::GPSYaw>("/origin_geo_point", 10);
origin_geo_point_pub_ = nh_private_.advertise<airsim_ros_pkgs::GPSYaw>("origin_geo_point", 10);

airsim_img_request_vehicle_name_pair_vec_.clear();
image_pub_vec_.clear();
Expand Down Expand Up @@ -980,6 +980,7 @@ void AirsimROSWrapper::lidar_timer_cb(const ros::TimerEvent& event)
auto lidar_data = airsim_client_.getLidarData(vehicle_lidar_pair.second, vehicle_lidar_pair.first); // airsim api is imu_name, vehicle_name
lck.unlock();
sensor_msgs::PointCloud2 lidar_msg = get_lidar_msg_from_airsim(lidar_data); // todo make const ptr msg to avoid copy
lidar_msg.header.frame_id = vehicle_lidar_pair.second; // sensor frame name. todo add to doc
lidar_msg.header.stamp = ros::Time::now();
lidar_pub_vec_[ctr].publish(lidar_msg);
ctr++;
Expand Down
60 changes: 60 additions & 0 deletions ros/src/airsim_tutorial_pkgs/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
# AirSim ROS Tutorials

This is a set of sample AirSim `settings.json`s, roslaunch and rviz files to give a starting point for using AirSim with ROS.
See [airsim_ros_pkgs](https://github.com/microsoft/AirSim/blob/master/ros/src/airsim_ros_pkgs/README.md) for the ROS API.


## Setup
```shell
$ cd PATH_TO/AirSim/ros
$ catkin build airsim_tutorial_pkgs
```

## Examples

### Single drone with monocular and depth cameras, and lidar
- Settings.json - [front_stereo_and_center_mono.json](https://github.com/microsoft/AirSim/blob/master/ros/src/airsim_tutorial_pkgs/settings/front_stereo_and_center_mono.json)
```shell
$ source PATH_TO/AirSim/ros/devel/setup.bash
$ roscd airsim_tutorial_pkgs
$ cp settings/front_stereo_and_center_mono.json ~/Documents/AirSim/settings.json

## Start your unreal package or binary here

$ roslaunch airsim_ros_pkgs airsim_node.launch;

# in a new pane / terminal
$ roslaunch airsim_tutorial_pkgs front_stereo_and_center_mono.launch
```
The above would start rviz with tf's, registered RGBD cloud using [depth_image_proc](https://wiki.ros.org/depth_image_proc) using the [`depth_to_pointcloud` launch file](https://github.com/microsoft/AirSim/master/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/depth_to_pointcloud.launch), and the lidar point cloud.


### Two drones, with cameras, lidar, IMU each
- Settings.json - [two_drones_camera_lidar_imu.json](https://github.com/microsoft/AirSim/blob/master/ros/src/airsim_tutorial_pkgs/settings/two_drones_camera_lidar_imu.json)

```shell
$ source PATH_TO/AirSim/ros/devel/setup.bash
$ roscd airsim_tutorial_pkgs
$ cp settings/two_drones_camera_lidar_imu.json ~/Documents/AirSim/settings.json

## Start your unreal package or binary here

$ roslaunch airsim_ros_pkgs airsim_node.launch;
$ roslaunch airsim_ros_pkgs rviz.launch
```
You can view the tfs in rviz. And do a `rostopic list` and `rosservice list` to inspect the services avaiable.

### Twenty-five drones in a square pattern
- Settings.json - [twenty_five_drones.json](https://github.com/microsoft/AirSim/blob/master/ros/src/airsim_tutorial_pkgs/settings/twenty_five_drones.json)

```shell
$ source PATH_TO/AirSim/ros/devel/setup.bash
$ roscd airsim_tutorial_pkgs
$ cp settings/twenty_five_drones.json ~/Documents/AirSim/settings.json

## Start your unreal package or binary here

$ roslaunch airsim_ros_pkgs airsim_node.launch;
$ roslaunch airsim_ros_pkgs rviz.launch
```
You can view the tfs in rviz. And do a `rostopic list` and `rosservice list` to inspect the services avaiable.
Loading

0 comments on commit 5e0864c

Please sign in to comment.