This is the official ROS driver for Zivid 3D cameras.
Note: Current version is 0.9.0. API and behavior are still subject to changes. When 1.0.0 is released the API will be stable.
Contents: Installation | Getting Started | Launching | Services | Topics | Configuration | Samples | FAQ
This driver supports Ubuntu 16.04 with ROS Kinetic and Ubuntu 18.04 with ROS Melodic. Follow the official ROS Wiki instructions to install ROS Kinetic Kame (for Ubuntu 16.04) or ROS Melodic Morenia (for Ubuntu 18.04).
Also install catkin and git:
sudo apt-get update
sudo apt-get install -y python-catkin-tools git
To use the ROS driver you need to download and install the "Zivid Core" package. Follow this guide to install Zivid for your version of Ubuntu. "Zivid Studio" and "Zivid Tools" packages are not required by the ROS driver, but can be useful for testing that your system has been setup correctly and that the camera is detected.
An OpenCL 1.2 compatible GPU and OpenCL driver is required by the Zivid SDK. Follow this guide to install OpenCL drivers for your system.
A C++17 compiler is required.
Ubuntu 16.04:
sudo apt-get install -y software-properties-common
sudo add-apt-repository -y ppa:ubuntu-toolchain-r/test
sudo apt-get update
sudo apt-get install -y g++-8
Ubuntu 18.04:
sudo apt-get install -y g++
First, load the setup.bash script into the current session.
Ubuntu 16.04:
source /opt/ros/kinetic/setup.bash
Ubuntu 18.04:
source /opt/ros/melodic/setup.bash
Create the workspace and src directory:
mkdir -p ~/catkin_ws/src
Clone the Zivid ROS project into the src directory:
cd ~/catkin_ws/src
git clone https://github.com/zivid/zivid-ros.git
Install dependencies:
cd ~/catkin_ws
sudo apt-get update
rosdep update
rosdep install --from-paths src --ignore-src -r -y
Finally, build the driver.
Ubuntu 16.04:
catkin build -DCMAKE_CXX_COMPILER=/usr/bin/g++-8
Ubuntu 18.04:
catkin build
Connect the Zivid camera to your USB3 port on your PC. You can use the ZividListCameras command-line tool available in the "Zivid Tools" package to confirm that your system has been configured correctly, and that the camera is discovered by your PC. You can also open Zivid Studio and connect to the camera. Close Zivid Studio before continuing with the rest of this guide.
Run the sample_capture_cpp.launch file to test that everything is working:
cd ~/catkin_ws && source devel/setup.bash
roslaunch zivid_samples sample_capture_cpp.launch
This launch file starts the zivid_camera
driver node, the sample_capture_cpp
node, as well as
rviz to visualize the point cloud and the 2D color and depth images
and rqt_reconfigure to adjust the camera settings.
The sample_capture_cpp
node will first configure the capture settings of the camera and then
trigger captures repeatedly. If everything is working, the output should be visible in rviz. Try to
adjust the exposure time or the iris in rqt_reconfigure and observe that the visualization in
rviz changes. Note: sometimes it is necessary to click "Refresh" in rqt_reconfigure to load the
configuration tree.
A more detailed description of the zivid_camera
driver follows below.
For sample code in C++ and Python, see the Sample nodes section.
It is required to specify a namespace when starting the driver. All the services, topics and configurations will be pushed into this namespace.
To launch the driver, first start roscore
in a seperate terminal window:
roscore
In another terminal run:
cd ~/catkin_ws && source devel/setup.bash
Then, launch the driver either as a node or a nodelet. To launch as a node:
ROS_NAMESPACE=zivid_camera rosrun zivid_camera zivid_camera_node
To launch as a nodelet:
ROS_NAMESPACE=zivid_camera rosrun nodelet nodelet standalone zivid_camera/nodelet
The following parameters can be specified when starting the driver. Note that all the parameters are optional, and typically not required to set.
For example, to launch the driver with frame_id
specified, append _frame_id:=camera1
to the
rosrun command:
ROS_NAMESPACE=zivid_camera rosrun zivid_camera zivid_camera_node _frame_id:=zivid
file_camera_path
(string, default: "")
Specify the path to a file camera to use instead of a real Zivid camera. This can be used to develop without access to hardware. The file camera returns the same point cloud for every capture. Click here to download a file camera.
frame_id
(string, default: "zivid_optical_frame")
Specify the frame_id used for all published images and point clouds.
num_capture_frames
(int, default: 10)
Specify the number of dynamic_reconfigure capture_frame nodes that are created during startup of the node. This number defines the maximum number of frames that can be a part of a single capture. All the capture_frames nodes that are created are by default enabled=false (see section Configuration). If you need to perform HDR with more than 10 enabled frames then increase this number. Otherwise it can be left as default.
serial_number
(string, default: "")
Specify the serial number of the Zivid camera to use. Important: When passing this value via the command line or rosparam the serial number must be prefixed with a colon (
:12345
). This parameter is optional. By default the driver will connect to the first available camera.
capture
(zivid_camera/Capture)
Invoke this service to trigger a capture. The capture settings are configured using dynamic_reconfigure, see section Configuration. When more than 1 frame is enabled an HDR capture is performed. The resulting point cloud and depth/color images are published as ROS topics.
camera_info/model_name
(zivid_camera/CameraInfoModelName)
Returns the camera's model name.
camera_info/serial_number
(zivid_camera/CameraInfoSerialNumber)
Returns the camera's serial number.
is_connected
(zivid_camera/IsConnected)
Returns if the camera is currently in
Connected
state (from the perspective of the ROS driver). The connection status is updated by the driver every 10 seconds and before eachcapture
service call. If the camera is not inConnected
state the driver will attempt to re-connect to the camera when it detects that the camera is available. This can happen if the camera is power-cycled or the USB cable is unplugged and then replugged.
color/camera_info
(sensor_msgs/CameraInfo)
Camera calibration and metadata.
color/image_color
(sensor_msgs/Image)
RGB image. The image is encoded as "rgb8".
depth/camera_info
(sensor_msgs/CameraInfo)
Camera calibration and metadata.
depth/image_raw
(sensor_msgs/Image)
Depth image. Each pixel contains the z-value (along the camera Z axis) in meters. The image is encoded as 32-bit float. Pixels where z-value is missing are NaN.
points
(sensor_msgs/PointCloud2)
Point cloud data. Each time a capture is invoked the resulting point cloud is published on this topic. The included point fields are x, y, z (in meters), c (contrast value), and r, g, b (colors). The output is in the camera's optical frame, where x is right, y is down and z is forward.
The capture settings can be configured using dynamic_reconfigure. Use rqt_reconfigure to view or change the settings using a GUI.
rosrun rqt_reconfigure rqt_reconfigure
The capture settings available in the zivid_camera
node matches the settings in the Zivid API.
To become more familiar with the available settings and what they do, see the API reference for the
Settings
class or use Zivid Studio.
The zivid_camera
node supports both single-capture and HDR-capture. HDR-capture works by taking
several individual captures (called frames) with different settings (for example different exposure time)
and combining the captures into one high-quality point cloud. For more information about HDR capture, visit our
knowledge base.
Note that the min, max and default value of the settings can change dependent on
what Zivid camera model you are using. Therefore you should not use the static __getMin()__
, __getMax()__
and
__getDefault()__
methods of the auto-generated C++ config classes (zivid_camera::CaptureGeneralConfig
and zivid_camera::CaptureFrameConfig
). Instead, you should query the server for the default values.
See the sample code for how to do this.
The available capture settings are organized into a hierarchy of configuration nodes:
/capture
/frame_0
...
/frame_1
...
...
/frame_9
...
/general
...
capture/frame_<n>/
contains settings for an individual frame. By default <n>
can be 0 to 9 for a
total of 10 frames. The total number of frames can be configured using the launch parameter num_capture_frames
(see section Launch Parameters above).
capture/frame_<n>/enabled
controls if frame <n>
will be included when the capture/
service is
invoked. If only one frame is enabled the capture/
service performs a single-capture. If more than
one frame is enabled the capture/
service will perform an HDR-capture. By default enabled is false.
In order to capture a point cloud at least one frame needs to be enabled.
Name | Type | Zivid API Setting | Note |
---|---|---|---|
capture/frame_<n>/bidirectional |
bool | Zivid::Settings::Bidirectional | |
capture/frame_<n>/brightness |
double | Zivid::Settings::Brightness | |
capture/frame_<n>/enabled |
bool | ||
capture/frame_<n>/exposure_time |
int | Zivid::Settings::ExposureTime | Specified in microseconds (µs) |
capture/frame_<n>/gain |
double | Zivid::Settings::Gain | |
capture/frame_<n>/iris |
int | Zivid::Settings::Iris |
capture/general
contains settings that apply to all frames in a capture.
Name | Type | Zivid API Setting |
---|---|---|
capture/general/blue_balance |
double | Zivid::Settings::BlueBalance |
capture/general/filters_contrast_enabled |
bool | Zivid::Settings::Filters::Contrast::Enabled |
capture/general/filters_contrast_threshold |
double | Zivid::Settings::Filters::Contrast::Threshold |
capture/general/filters_gaussian_enabled |
bool | Zivid::Settings::Filters::Gaussian::Enabled |
capture/general/filters_gaussian_sigma |
double | Zivid::Settings::Filters::Gaussian::Sigma |
capture/general/filters_outlier_enabled |
bool | Zivid::Settings::Filters::Outlier::Enabled |
capture/general/filters_outlier_threshold |
double | Zivid::Settings::Filters::Outlier::Threshold |
capture/general/filters_reflection_enabled |
bool | Zivid::Settings::Filters::Reflection::Enabled |
capture/general/filters_saturated_enabled |
bool | Zivid::Settings::Filters::Saturated::Enabled |
capture/general/red_balance |
double | Zivid::Settings::RedBalance |
In the zivid_samples
package we have added example nodes in C++ and Python that demonstrate
how to use the Zivid ROS driver. These nodes can be used as a starting point for your project.
This sample performs single-captures repeatedly. This sample shows how to configure the capture
settings using dynamic_reconfigure, how to subscribe to
the points
topic, and how to invoke the capture
service.
C++ (Source code)
Using roslaunch (also launches roscore
, zivid_camera
, rviz
and rqt_reconfigure
):
roslaunch zivid_samples sample_capture_cpp.launch
Using rosrun (when roscore
and zivid_camera
are running):
rosrun zivid_samples sample_capture_cpp
Python (Source code)
Using roslaunch (also launches roscore
, zivid_camera
, rviz
and rqt_reconfigure
):
roslaunch zivid_samples sample_capture_py.launch
Using rosrun (when roscore
and zivid_camera
are running):
rosrun zivid_samples sample_capture.py
zivid_camera_with_settings.launch starts
the zivid_camera
node with capture settings set to 3-frame HDR. Modify the settings in this .launch
file to match your scene.
roslaunch zivid_samples zivid_camera_with_settings.launch
ROS_NAMESPACE=zivid_camera roslaunch zivid_camera visualize.launch
You can use multiple Zivid cameras simultaneously by starting one node per camera and specifying unique namespaces per node:
ROS_NAMESPACE=camera1 rosrun zivid_camera zivid_camera_node
ROS_NAMESPACE=camera2 rosrun zivid_camera zivid_camera_node
By default the zivid_camera node will connect to the first available/unused camera. We recommend that
you first start the first node, wait for it to be ready (for example, by waiting for the capture
service to be available), then start the second node. This avoids any race conditions where both nodes
may try to connect to the same camera at the same time.
This project comes with a set of unit and module tests to verify the provided functionality. To run the tests locally, first download and install the file camera used for testing:
wget -q https://www.zivid.com/software/ZividSampleData.zip
unzip ./ZividSampleData.zip
rm ./ZividSampleData.zip
sudo mkdir -p /usr/share/Zivid/data/
sudo cp ./MiscObjects.zdf /usr/share/Zivid/data/
rm ./MiscObjects.zdf
Then run the tests:
cd ~/catkin_ws && source devel/setup.bash
catkin run_tests && catkin_test_results
The tests can also be run via docker. See the Azure Pipelines configuration file for details.
The node logs extra information at log level debug, including the settings used when capturing. Enable debug logging to troubleshoot issues.
rosconsole set /<namespace>/zivid_camera ros.zivid_camera debug
For example, if ROS_NAMESPACE=zivid_camera,
rosconsole set /zivid_camera/zivid_camera ros.zivid_camera debug
catkin build -DCOMPILER_WARNINGS=ON
This project is licensed under BSD 3-clause license, see the LICENSE file for details.
Please report any issues or feature requests related to the ROS driver in the issue tracker. Visit Zivid Knowledge Base for general help on using Zivid 3D cameras. If you cannot find a solution to your issue, please contact [email protected].
This FTP (Focused Technical Project) has received funding from the European Union's Horizon 2020 research and innovation programme under the project ROSIN with the grant agreement No 732287. For more information, visit rosin-project.eu.