From 5e0864cdaed4c8a62fd43fe26866a05bc09ef1ea Mon Sep 17 00:00:00 2001 From: madratman Date: Mon, 13 May 2019 15:32:30 -0700 Subject: [PATCH] [ros] fix lidar tf, added docs and examples --- README.md | 2 +- ros/src/airsim_ros_pkgs/README.md | 44 ++- .../src/airsim_ros_wrapper.cpp | 3 +- ros/src/airsim_tutorial_pkgs/README.md | 60 ++++ .../front_stereo_and_center_mono/default.rviz | 285 ++++++++++++++++++ .../depth_to_pointcloud.launch | 8 +- .../front_stereo_and_center_mono/rviz.launch | 2 +- .../front_stereo_and_center_mono.json | 4 +- 8 files changed, 374 insertions(+), 34 deletions(-) create mode 100644 ros/src/airsim_tutorial_pkgs/README.md create mode 100644 ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/default.rviz diff --git a/README.md b/README.md index 9ef60001e9..803b3a1aaa 100644 --- a/README.md +++ b/README.md @@ -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) diff --git a/ros/src/airsim_ros_pkgs/README.md b/ros/src/airsim_ros_pkgs/README.md index eecd9fd943..5bcc9d94c0 100644 --- a/ros/src/airsim_ros_pkgs/README.md +++ b/ros/src/airsim_ros_pkgs/README.md @@ -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] @@ -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: @@ -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) @@ -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`. \ No newline at end of file + - You can open terminator in a new window by entering `$ DISPLAY=:0 terminator -u`. diff --git a/ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp b/ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp index 60935aab5d..88952836da 100644 --- a/ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp +++ b/ros/src/airsim_ros_pkgs/src/airsim_ros_wrapper.cpp @@ -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("/origin_geo_point", 10); + origin_geo_point_pub_ = nh_private_.advertise("origin_geo_point", 10); airsim_img_request_vehicle_name_pair_vec_.clear(); image_pub_vec_.clear(); @@ -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++; diff --git a/ros/src/airsim_tutorial_pkgs/README.md b/ros/src/airsim_tutorial_pkgs/README.md new file mode 100644 index 0000000000..340983e0ef --- /dev/null +++ b/ros/src/airsim_tutorial_pkgs/README.md @@ -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. diff --git a/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/default.rviz b/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/default.rviz new file mode 100644 index 0000000000..00dc9c7762 --- /dev/null +++ b/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/default.rviz @@ -0,0 +1,285 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /TF1/Frames1 + - /Odometry1/Shape1 + Splitter Ratio: 0.87308532 + Tree Height: 775 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679016 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: front_left_depth_planar_registered_point_cloud +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.0299999993 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: false + LidarCustom: + Value: true + drone_1: + Value: true + drone_1/odom_local_ned: + Value: true + front_center_custom_body: + Value: false + front_center_custom_body/static: + Value: false + front_center_custom_optical: + Value: true + front_center_custom_optical/static: + Value: true + front_left_custom_body: + Value: false + front_left_custom_body/static: + Value: false + front_left_custom_optical: + Value: true + front_left_custom_optical/static: + Value: true + front_right_custom_body: + Value: false + front_right_custom_body/static: + Value: false + front_right_custom_optical: + Value: true + front_right_custom_optical/static: + Value: true + world_enu: + Value: false + world_ned: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + world_ned: + drone_1: + drone_1/odom_local_ned: + LidarCustom: + {} + front_center_custom_body/static: + {} + front_center_custom_optical/static: + {} + front_left_custom_body/static: + {} + front_left_custom_optical/static: + {} + front_right_custom_body/static: + {} + front_right_custom_optical/static: + {} + front_center_custom_body: + {} + front_center_custom_optical: + {} + front_left_custom_body: + {} + front_left_custom_optical: + {} + front_right_custom_body: + {} + front_right_custom_optical: + {} + world_enu: + {} + Update Interval: 0 + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: RGB8 + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: front_left_depth_planar_registered_point_cloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.100000001 + Style: Flat Squares + Topic: /airsim_node/drone_1/front_left_custom/DepthPlanner/registered/points + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + - Angle Tolerance: 0.100000001 + Class: rviz/Odometry + Covariance: + Orientation: + Alpha: 0.5 + Color: 255; 255; 127 + Color Style: Unique + Frame: Local + Offset: 1 + Scale: 1 + Value: true + Position: + Alpha: 0.300000012 + Color: 204; 51; 204 + Scale: 1 + Value: true + Value: true + Enabled: true + Keep: 25 + Name: Odometry + Position Tolerance: 0.100000001 + Shape: + Alpha: 1 + Axes Length: 1 + Axes Radius: 0.100000001 + Color: 255; 25; 0 + Head Length: 0.200000003 + Head Radius: 0.0500000007 + Shaft Length: 0.200000003 + Shaft Radius: 0.0199999996 + Value: Arrow + Topic: /airsim_node/MyQuad/odom_local_ned + Unreliable: false + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 4096 + Min Color: 0; 0; 0 + Min Intensity: 0 + Name: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.100000001 + Style: Points + Topic: /airsim_node/drone_1/lidar/LidarCustom + Unreliable: false + Use Fixed Frame: true + Use rainbow: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: world_enu + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 30.6555023 + Enable Stereo Rendering: + Stereo Eye Separation: 0.0599999987 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.525829852 + Y: 2.05633426 + Z: -0.726522326 + Focal Shape Fixed Size: false + Focal Shape Size: 0.0500000007 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.00999999978 + Pitch: 0.309797317 + Target Frame: world_view + Value: Orbit (rviz) + Yaw: 4.59035587 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1056 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 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 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1875 + X: 1965 + Y: 24 diff --git a/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/depth_to_pointcloud.launch b/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/depth_to_pointcloud.launch index 3deeac0488..ed8ed20109 100644 --- a/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/depth_to_pointcloud.launch +++ b/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/depth_to_pointcloud.launch @@ -10,9 +10,9 @@ - - - - + + + + \ No newline at end of file diff --git a/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/rviz.launch b/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/rviz.launch index 6a39c5e639..b5e8d324a2 100644 --- a/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/rviz.launch +++ b/ros/src/airsim_tutorial_pkgs/launch/front_stereo_and_center_mono/rviz.launch @@ -1,3 +1,3 @@ - + \ No newline at end of file diff --git a/ros/src/airsim_tutorial_pkgs/settings/front_stereo_and_center_mono.json b/ros/src/airsim_tutorial_pkgs/settings/front_stereo_and_center_mono.json index 36a251606f..5672ffa357 100644 --- a/ros/src/airsim_tutorial_pkgs/settings/front_stereo_and_center_mono.json +++ b/ros/src/airsim_tutorial_pkgs/settings/front_stereo_and_center_mono.json @@ -5,7 +5,7 @@ "ViewMode": "SpringArmChase", "ClockSpeed": 1.0, "Vehicles": { - "MyQuad": { + "drone_1": { "VehicleType": "SimpleFlight", "DefaultVehicleState": "Armed", "EnableCollisionPassthrogh": false, @@ -86,7 +86,7 @@ "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0 } }, - "X": 0, "Y": 0, "Z": 0, + "X": 2, "Y": 0, "Z": 0, "Pitch": 0, "Roll": 0, "Yaw": 0 } },