Skip to content

Commit

Permalink
Tutorials feat (#282)
Browse files Browse the repository at this point in the history
* New folder "Tutorials" with tutorials about Video, Depth and Pose subscription
* Reorganized the plugin structure in RVIZ display
* Removed OpenCV dependency
* Added Floor Alignment feature
* Added Covariance information to the odometry message
* Added Odometry and Pose paths
* Added the new topic "pose_with_covariance"
* New documentation
* Fixed reconnection issue. Thanks to @RhysMcK
* Bug fixes
  • Loading branch information
Myzhar authored and adujardin committed Sep 21, 2018
1 parent f9c4b56 commit 1a22502
Show file tree
Hide file tree
Showing 47 changed files with 2,823 additions and 1,543 deletions.
20 changes: 14 additions & 6 deletions README.md
@@ -1,7 +1,11 @@
![](./images/Picto+STEREOLABS_Black.png)

# Stereolabs ZED Camera - ROS Integration

This package lets you use the ZED stereo camera with ROS. It outputs the camera left and right images, depth map, point cloud, pose information and supports the use of multiple ZED cameras.

[More information](https://www.stereolabs.com/documentation/guides/using-zed-with-ros/introduction.html)

## Getting started

- First, download the latest version of the ZED SDK on [stereolabs.com](https://www.stereolabs.com/developers/)
Expand All @@ -25,7 +29,6 @@ The zed_ros_wrapper is a catkin package. It depends on the following ROS package
- rosconsole
- sensor_msgs
- stereo_msgs
- opencv3
- image_transport
- dynamic_reconfigure
- urdf
Expand Down Expand Up @@ -57,12 +60,17 @@ To launch the wrapper without Rviz, use:

$ roslaunch zed_wrapper zed.launch serial_number:=1010 #replace 1010 with the actual SN

### Modules
### Examples

Alongside the wrapper itself and the Rviz display, a few examples are provided to interface the ZED with other ROS packages :

Alongside the wrapper itself and the Rviz display, a few other modules are provided to interface the ZED with other ROS packages :
- [RTAB-Map](http://introlab.github.io/rtabmap/) : See [zed_rtabmap_example](./examples/zed_rtabmap_example)
- ROS Nodelet, `depthimage_to_laserscan` : See [zed_nodelet_example](./examples/zed_nodelet_example)

- [RTAB-Map](http://introlab.github.io/rtabmap/) : See [zed_rtabmap_example](./zed_rtabmap_example)
- ROS Nodelet, `depthimage_to_laserscan` : See [zed_nodelet_example](./zed_nodelet_example)
### Tutorials

A few tutorials are provided to understand how to use the ZED node in the ROS environment :

[More](https://www.stereolabs.com/documentation/guides/using-zed-with-ros/introduction.html)
- Video subscribing : See [zed_video_sub_tutorial](./tutorials/zed_video_sub_tutorial)
- Depth subscribing : See [zed_depth_sub_tutorial](./tutorials/zed_depth_sub_tutorial)
- Positional Tracking subscribing : See [zed_tracking_sub_tutorial](./tutorials/zed_tracking_sub_tutorial)
6 changes: 6 additions & 0 deletions examples/README.md
@@ -0,0 +1,6 @@
# Examples
How to use the ZED ROS node with other ROS packages

* `zed_nodelet_example`: shows how to use the nodelet intraprocess communication to generate a virtual laser scan using the [depthimage_to_laserscan](http://wiki.ros.org/depthimage_to_laserscan) package

* `zed_rtabmap_example`: shows how to use the ZED with the RTABMap package to generate a 3D map with the [rtabmap_ros](http://wiki.ros.org/rtabmap_ros) package
File renamed without changes.
69 changes: 69 additions & 0 deletions examples/zed_nodelet_example/README.md
@@ -0,0 +1,69 @@
# Stereolabs ZED Camera - ROS Nodelet example

`zed_nodelet_example` is a ROS package to illustrate how to load the `ZEDWrapperNodelet` with an external nodelet manager and use the intraprocess communication to generate a virtual laser scan thanks to the nodelet `depthimage_to_laserscan`

## Run the program

To launch the wrapper nodelet along with the `depthimage_to_laserscan` nodelet, open a terminal and launch:

`$ roslaunch zed_nodelet_example zed_nodelet_laserscan.launch`

**Note**: Remember to change the parameter `camera_model` to `0` if you are using a **ZED** or to `1` if you are using a **ZED Mini**

## Visualization
To visualize the result of the process open Rviz, add a `LaserScan` visualization and set `/zed/scan` as `topic` parameter

Virtual 2D laser scan rendered in Rviz. You can see the projection of the virtual laser scan on the RGB image on the left
![Virtual laser scan rendered in Rviz](images/laserscan.png)

Virtual 2D laser scan rendered in Rviz over the 3D depth cloud. You can see the projection of the virtual laser scan on the RGB image on the left
![Virtual laser scan rendered in Rviz on the Depthcloud](images/laserscan-depthcloud.png)

## The launch file explained
The launch file executes three main operations:

1. Runs the Nodelet manager
2. Load the ZED nodelet
3. Load the `depthimage_to_laserscan` nodelet

To run the Nodelet Manager we use the following line instruction:

```<node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager_name)" args="manager" output="screen" />```

the Nodelet Manager is the process that loads the ZED and the depthimage_to_laserscan nodelets and that allows them to us intra-process communication to pass elaboration data.

The "variable" `nodelet_manager_name` is defined here:

```<arg name="nodelet_manager_name" default="zed_nodelet_manager" />```

The ZED nodelet is loaded using its own nodelet launch file:

```<include file="$(find zed_wrapper)/launch/zed_camera_nodelet.launch">```

called passing the "variable" `nodelet_manager_name` as parameter:

```<arg name="nodelet_manager_name" value="$(arg nodelet_manager_name)" />```

The `DepthImageToLaserScanNodelet` nodelet is loaded with the following commands:
```
<node pkg="nodelet" type="nodelet" name="depthimage_to_laserscan" args="load depthimage_to_laserscan/DepthImageToLaserScanNodelet zed_nodelet_manager">
<param name="scan_height" value="10"/>
<param name="output_frame_id" value="$(arg left_camera_frame)"/>
<param name="range_min" value="0.45"/>
<remap from="image" to="$(arg depth_topic)"/>
</node>
```

it is really important to notice these two lines:

```<param name="output_frame_id" value="$(arg left_camera_frame)"/>```

```<remap from="image" to="$(arg depth_topic)"/>```

The first line tells to the `depthimage_to_laserscan` nodelet which is the frame name of the virtual scan message.

The second line tells to the `depthimage_to_laserscan` nodelet which is the depth image topic to use to extract the information to generate the virtual laser scan.

For the description of the other parameters please refer to the [documentation of the `depthimage_to_laserscan` package](http://wiki.ros.org/depthimage_to_laserscan)


File renamed without changes
Expand Up @@ -37,7 +37,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
<arg name="nodelet_manager_name" default="zed_nodelet_manager" />

<group ns="zed">
<!-- Nodelet Manager -->
<!-- Nodelet Manager -->
<node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager_name)" args="manager" output="screen" />

<!-- ZED wrapper as nodelet -->
Expand Down
@@ -1,11 +1,11 @@
<?xml version="1.0"?>
<package format="2">
<name>zed_nodelet_example</name>
<version>1.0.0</version>
<version>2.6.0</version>
<description>
"zed_nodelet_example" is a ROS package to illustrate how to load the ZEDWrapperNodelet with an external nodelet manager and use the intraprocess communication.
</description>
<maintainer email="developers@stereolabs.com">STEREOLABS</maintainer>
<maintainer email="support@stereolabs.com">STEREOLABS</maintainer>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>
Expand Down
File renamed without changes.
54 changes: 54 additions & 0 deletions examples/zed_rtabmap_example/README.md
@@ -0,0 +1,54 @@
# Stereolabs ZED Camera - RTAB-map example

This package shows how to use the ZED Wrapper with [RTAB-map](http://introlab.github.io/rtabmap/)

## Run the program

To launch the example, open a terminal and launch:

$ roslaunch zed_rtabmap_example zed_rtabmap.launch

Example of indoor 3D mapping using RTAB-map and ZED

![Example of indoor 3D mapping](images/rtab-map.png)

## The launch file explained

To correctly use the ZED wrapper with the `rtabmap_ros` node we need to match the following RTABmap parameters:

- `rgb_topic` -> topic of the color information to be associated to the points of the 3D map
- `depth_topic` -> topic of the depth information
- `camera_info_topic` -> topic of RGB camera parameters used to create the association of each color pixel to the relative 3D point
- `depth_camera_info_topic` -> topic of the depth camera parameter, to convert the 2D depth image to a 3D point cloud
- `frame_id` -> name of the camera frame

The values associated to the above parameters are the following:

```
<arg name="rgb_topic" default="/rgb/image_rect_color" />
<arg name="depth_topic" default="/depth/depth_registered" />
<arg name="camera_info_topic" default="/rgb/camera_info" />
<arg name="depth_camera_info_topic" default="/depth/camera_info" />
<arg name="camera_frame" default="zed_camera_center" />
```

The corresponding parameters of the ZED node are the following:

- `rgb_topic` -> `rgb_topic`
- `depth_topic` -> `depth_topic`
- `camera_info_topic` -> `rgb_info_topic`
- `depth_camera_info_topic` -> `depth_cam_info_topic`
- `frame_id` -> `base_frame`

The corresponding parameters of the `rtabmap_ros` node are the following:

- `rgb_topic` -> `rgb_topic`
- `depth_topic` -> `depth_topic`
- `camera_info_topic` -> `rgb_info_topic`
- `depth_camera_info_topic` -> `depth_cam_info_topic`
- `camera_frame` -> `frame_id`





File renamed without changes
Expand Up @@ -47,16 +47,16 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
<arg name="frame_rate" value="$(arg frame_rate)" />
<arg name="verbose" value="$(arg verbose)" />

<arg name="rgb_topic" value="$(arg rgb_topic)" />
<arg name="depth_topic" value="$(arg depth_topic)" />
<arg name="rgb_topic" value="$(arg rgb_topic)" />
<arg name="depth_topic" value="$(arg depth_topic)" />
<arg name="rgb_info_topic" value="$(arg camera_info_topic)" />
<arg name="depth_cam_info_topic" value="$(arg depth_camera_info_topic)" />
<arg name="base_frame" value="$(arg camera_frame)" />
<arg name="base_frame" value="$(arg camera_frame)" />
</include>

<!-- RTAB-map Node-->
<include file="$(find rtabmap_ros)/launch/rtabmap.launch">
<arg name="rtabmap_args" value="--delete_db_on_start" />
<arg name="rtabmap_args" value="--delete_db_on_start" />
<arg name="rgb_topic" value="$(arg rgb_topic)" />
<arg name="depth_topic" value="$(arg depth_topic)" />
<arg name="camera_info_topic" value="$(arg camera_info_topic)" />
Expand Down
@@ -1,11 +1,11 @@
<?xml version="1.0"?>
<package format="2">
<name>zed_rtabmap_example</name>
<version>1.0.0</version>
<version>2.6.0</version>
<description>
"zed_rtabmap_example" is a ROS package to show how to use the ROS wrapper with <a href="http://introlab.github.io/rtabmap/">"RTAB-MAP"</a>
</description>
<maintainer email="developers@stereolabs.com">STEREOLABS</maintainer>
<maintainer email="support@stereolabs.com">STEREOLABS</maintainer>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>
Expand Down
Binary file added images/Picto+STEREOLABS_Black.png
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
14 changes: 14 additions & 0 deletions tutorials/README.md
@@ -0,0 +1,14 @@
# Tutorials
A series of tutorials are provided to better understand how to use the ZED node in the ROS environment :

- [Video subscribing](./zed_video_sub_tutorial) : `zed_video_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type `sensor_msgs/Image` to retrieve the Left and Right rectified images published by the ZED node

- [Depth subscribing](./zed_depth_sub_tutorial) : `zed_depth_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type `sensor_msgs/Image` to retrieve the depth images published by the ZED node and to get the measured distance at the center of the image

- [Positional tracking subscribing](./zed_tracking_sub_tutorial) : `zed_tracking_sub_tutorial` - in this tutorial you will learn how to write a simple node that subscribes to messages of type `geometry_msgs/PoseStamped` and `nav_msgs/Odometry` to retrieve the position and the orientation of the ZED camera in the map and in the odometry frames.

For a complete explanation of the tutorials please refer to the Stereolabs ZED online documentation:

- [Video](https://docs.stereolabs.com/integrations/ros/video/)
- [Depth](https://docs.stereolabs.com/integrations/ros/depth_sensing/)
- [Positional Tracking](https://docs.stereolabs.com/integrations/ros/positional_tracking/)
Binary file added tutorials/images/tutorial_depth.png
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added tutorials/images/tutorial_tracking.png
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added tutorials/images/tutorial_video.png
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
19 changes: 19 additions & 0 deletions tutorials/zed_depth_sub_tutorial/CMakeLists.txt
@@ -0,0 +1,19 @@
cmake_minimum_required(VERSION 2.8.3)
project(zed_depth_sub_tutorial)

# if CMAKE_BUILD_TYPE is not specified, take 'Release' as default
IF(NOT CMAKE_BUILD_TYPE)
SET(CMAKE_BUILD_TYPE Release)
ENDIF(NOT CMAKE_BUILD_TYPE)

## Find catkin and any catkin packages
find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs)

## Declare a catkin package
catkin_package()

include_directories(include ${catkin_INCLUDE_DIRS})

## Build
add_executable(zed_depth_sub src/zed_depth_sub_tutorial.cpp)
target_link_libraries(zed_depth_sub ${catkin_LIBRARIES})
9 changes: 9 additions & 0 deletions tutorials/zed_depth_sub_tutorial/README.md
@@ -0,0 +1,9 @@
# Depth subscription tutorial

In this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the depth images published by the ZED node and to get the measured distance at the center of the image

![](../images/tutorial_depth.png)

The complete documentation is available on the [Stereolabs website](https://docs.stereolabs.com/integrations/ros/depth_sensing/)


14 changes: 14 additions & 0 deletions tutorials/zed_depth_sub_tutorial/package.xml
@@ -0,0 +1,14 @@
<package format="2">
<name>zed_depth_sub_tutorial</name>
<version>2.6.0</version>
<description>
This package is a tutorial showing how to subscribe to ZED depth streams
</description>
<maintainer email="support@stereolabs.com">STEREOLABS</maintainer>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>

<depend>roscpp</depend>
<depend>sensor_msgs</depend>
</package>
98 changes: 98 additions & 0 deletions tutorials/zed_depth_sub_tutorial/src/zed_depth_sub_tutorial.cpp
@@ -0,0 +1,98 @@
///////////////////////////////////////////////////////////////////////////
//
// Copyright (c) 2018, STEREOLABS.
//
// All rights reserved.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
///////////////////////////////////////////////////////////////////////////

/**
* This tutorial demonstrates simple receipt of ZED depth messages over the ROS system.
*/

#include <ros/ros.h>
#include <sensor_msgs/Image.h>

/**
* Subscriber callback
*/

void depthCallback(const sensor_msgs::Image::ConstPtr& msg) {

// Get a pointer to the depth values casting the data
// pointer to floating point
float* depths = (float*)(&msg->data[0]);

// Image coordinates of the center pixel
int u = msg->width / 2;
int v = msg->height / 2;

// Linear index of the center pixel
int centerIdx = u + msg->width * v;

// Output the measure
ROS_INFO("Center distance : %g m", depths[centerIdx]);
}

/**
* Node main function
*/
int main(int argc, char** argv) {
/**
* The ros::init() function needs to see argc and argv so that it can perform
* any ROS arguments and name remapping that were provided at the command line.
* For programmatic remappings you can use a different version of init() which takes
* remappings directly, but for most command-line programs, passing argc and argv is
* the easiest way to do it. The third argument to init() is the name of the node.
*
* You must call one of the versions of ros::init() before using any other
* part of the ROS system.
*/
ros::init(argc, argv, "zed_video_subscriber");

/**
* NodeHandle is the main access point to communications with the ROS system.
* The first NodeHandle constructed will fully initialize this node, and the last
* NodeHandle destructed will close down the node.
*/
ros::NodeHandle n;

/**
* The subscribe() call is how you tell ROS that you want to receive messages
* on a given topic. This invokes a call to the ROS
* master node, which keeps a registry of who is publishing and who
* is subscribing. Messages are passed to a callback function, here
* called imageCallback. subscribe() returns a Subscriber object that you
* must hold on to until you want to unsubscribe. When all copies of the Subscriber
* object go out of scope, this callback will automatically be unsubscribed from
* this topic.
*
* The second parameter to the subscribe() function is the size of the message
* queue. If messages are arriving faster than they are being processed, this
* is the number of messages that will be buffered up before beginning to throw
* away the oldest ones.
*/
ros::Subscriber subDepth = n.subscribe("/zed/depth/depth_registered", 10, depthCallback);


/**
* ros::spin() will enter a loop, pumping callbacks. With this version, all
* callbacks will be called from within this thread (the main one). ros::spin()
* will exit when Ctrl-C is pressed, or the node is shutdown by the master.
*/
ros::spin();

return 0;
}

0 comments on commit 1a22502

Please sign in to comment.