Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
57 commits
Select commit Hold shift + click to select a range
fed6f70
Add internal IMU data publisher by ros::Timer
tongtybj Jun 5, 2018
291ccf5
Modification for a correct merge
Myzhar Jun 25, 2018
c218cd2
Merge branch 'tongtybj-imu_pub' into devel
Myzhar Jun 25, 2018
4378c2e
Merge pull request #217 from stereolabs/master
Myzhar Jun 25, 2018
e1c80d9
Merge pull request #218 from stereolabs/master
Myzhar Jun 25, 2018
90fe983
Corrected issue with IMU reference frame
Myzhar Jun 26, 2018
845e96b
Code reformatting
Myzhar Jun 26, 2018
c893e79
Removed unuseful parameters from publisher functions that were using …
Myzhar Jun 26, 2018
1a7857c
Merged PR #189 : Add publisher for disparity
Myzhar Jun 26, 2018
f2bbd93
Added launch example to run ZED as a nodelet with ROS nodelet manager
Myzhar Jun 27, 2018
9571146
Code refactoring
Myzhar Jun 27, 2018
7c45753
Code refactoring
Myzhar Jun 27, 2018
19e1f0c
Added coordinate system conversion to ROS according to ZED SDK version
Myzhar Jun 27, 2018
633b848
Improved performances using OpenMP
Myzhar Jun 28, 2018
4870071
Modify resolution by launch file
Myzhar Jun 28, 2018
1157cfe
Coordinate changes for Z_UP-X_FWD removed
Myzhar Jun 28, 2018
68d472d
Added ROS service to request resetTracking to ZED SDK
Myzhar Jun 29, 2018
5d0d7fe
Reorganized ZED TF Tree according to ROS conventions
Myzhar Jun 29, 2018
027aabc
Minor changes to file names and code order
Myzhar Jul 2, 2018
f44f0e3
Fixed compilation error with SDK minor than v2.5.x
Myzhar Jul 2, 2018
7f939a5
Fixed issue #212 : zed-wrapper-node running on TX2 freezes when no
Myzhar Jul 2, 2018
a5eec02
Publishing odometry when depth_map topic is subscribed (same as for
Myzhar Jul 2, 2018
2563432
Added publishers for Confidence Image (8 bit) and Confidence Map (float)
Myzhar Jul 2, 2018
d9e88e9
Exposed enable_pose_smoothing and enable_spatial_memory params for
Myzhar Jul 3, 2018
8fa4b52
Exposed "initial_pose" to initialize tracking position
Myzhar Jul 3, 2018
f664f87
Modified "reset_tracking" to reset to "initial_pose" from Param Server
Myzhar Jul 3, 2018
452aaa8
Added service to set pose
Myzhar Jul 4, 2018
29c681b
Fixed issue with "Camera info" when setting new "mat_resize_factor"
Myzhar Jul 5, 2018
9f44001
Added missing set_pose.srv
Myzhar Jul 5, 2018
8c279bd
Removed odometry and replaced with "map pose"
Myzhar Jul 5, 2018
ae74d6c
Fixes the "unchecking/checking" depth cloud problem
Myzhar Jul 5, 2018
9178296
Added tool function slTime2Ros to fix timestamp
Myzhar Jul 5, 2018
195fd68
Coordinate changing code cleaned
Myzhar Jul 6, 2018
95bdebd
Added "imu/data_raw" topic according to ROS REP145
Myzhar Jul 6, 2018
f0be773
Update to publish IMU TF and topics at about 500 Hz
Myzhar Jul 6, 2018
d7ccb07
Added IMU R,t transform to zed_camera_center [TO BE CHECKED]
Myzhar Jul 6, 2018
a6f4136
Fixed issue with IMU link timestamp
Myzhar Jul 9, 2018
c226489
Added back odometry frame (together with map)
Myzhar Jul 9, 2018
b9b9659
Fixed IMU reference frame
Myzhar Jul 10, 2018
5087218
Fixed odometry transformation. Delta movements that are in camera frame
Myzhar Jul 11, 2018
ffc7ad3
Fixed IMU frame publishing
Myzhar Jul 12, 2018
22014ee
Added "verbose" parameter as for zendesk request
Myzhar Jul 12, 2018
668911d
Removed unuseful `include`
Myzhar Jul 13, 2018
e627f2c
Uniformed member variable names to camel case
Myzhar Jul 13, 2018
9c5c346
Modified logger level automatically to "Debug" if node is compiled with
Myzhar Jul 13, 2018
832be65
Added debug info about working thread duration in case it does not
Myzhar Jul 13, 2018
0c38c3a
Exposed "frame_rate" to "zed.launch" file
Myzhar Jul 13, 2018
6f04504
Added option "init_odom_with_imu" to initialize odometry with first pose
Myzhar Jul 16, 2018
8d7220b
Added check on the couple "resolution/framerate".
Myzhar Jul 16, 2018
544f74d
Updated all launch files to latest modifications
Myzhar Jul 16, 2018
3a98446
Fixed bug when the couple "resolution/framerate" was valid
Myzhar Jul 16, 2018
edc4e0f
Added service to reset odometry and clear drift errors.
Myzhar Jul 16, 2018
88bffb2
Exposed the SVO and Odometry Frame parameters to "zed.launch"
Myzhar Jul 16, 2018
7f8d8cf
Reduced the number of warning messages in the case that elaboration time
Myzhar Jul 16, 2018
775a963
Fixed "SIGTERM if no ZED was open" using the Serial Number
Myzhar Jul 16, 2018
1f0d41d
Code cleaning
Myzhar Jul 16, 2018
9c7c434
Fix for IMU TF not propagating in Rviz
Myzhar Jul 16, 2018
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
51 changes: 42 additions & 9 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,27 +38,47 @@ checkPackage("CUDA" "CUDA not found, install it from:\n https://developer.nvidia
find_package(PCL)
checkPackage("PCL" "PCL not found, try to install it with:\n sudo apt-get install libpcl1 ros-$(rosversion -d)-pcl-ros")

find_package(OpenMP)
checkPackage("OpenMP" "OpenMP not found, please install it to improve performances: 'sudo apt install libomp-dev'")
if (OPENMP_FOUND)
set (CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}")
set (CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}")
set (CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}")
endif()

find_package(catkin COMPONENTS
image_transport
roscpp
rosconsole
sensor_msgs
stereo_msgs
dynamic_reconfigure
tf2_ros
pcl_conversions
nodelet
tf2_geometry_msgs
message_generation
)

checkPackage("image_transport" "")
checkPackage("roscpp" "")
checkPackage("rosconsole" "")
checkPackage("sensor_msgs" "")
checkPackage("stereo_msgs" "")
checkPackage("dynamic_reconfigure" "")
checkPackage("tf2_ros" "")
checkPackage("pcl_conversions" "")
checkPackage("nodelet" "")
checkPackage("tf2_geometry_msgs" "")
checkPackage("message_generation" "")

add_service_files( FILES
set_initial_pose.srv
reset_odometry.srv
reset_tracking.srv
)

generate_messages()

generate_dynamic_reconfigure_options(
cfg/Zed.cfg
Expand All @@ -69,23 +89,37 @@ catkin_package(
roscpp
rosconsole
sensor_msgs
stereo_msgs
opencv3
image_transport
dynamic_reconfigure
tf2_ros
tf2_geometry_msgs
pcl_conversions
pcl_conversions
message_runtime
)

###############################################################################
# SOURCES

set(TOOLS_SRC ${CMAKE_CURRENT_SOURCE_DIR}/src/tools/src/sl_tools.cpp)
set(NODE_SRC ${CMAKE_CURRENT_SOURCE_DIR}/src/zed_wrapper_node.cpp)
set(NODELET_SRC ${CMAKE_CURRENT_SOURCE_DIR}/src/nodelet/src/zed_wrapper_nodelet.cpp)

###############################################################################

###############################################################################
# INCLUDES

# Specify locations of header files.
include_directories(
${catkin_INCLUDE_DIRS}
${CUDA_INCLUDE_DIRS}
${ZED_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
${CUDA_INCLUDE_DIRS}
${ZED_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${CMAKE_CURRENT_SOURCE_DIR}/src/tools/include
${CMAKE_CURRENT_SOURCE_DIR}/src/nodelet/include
)

link_directories(${ZED_LIBRARY_DIR})
Expand All @@ -98,7 +132,6 @@ link_directories(${PCL_LIBRARY_DIRS})
###############################################################################
# EXECUTABLE


if(NOT DEFINED CUDA_NPP_LIBRARIES_ZED)
#To deal with cuda 9 nppi libs and previous versions of ZED SDK
set(CUDA_NPP_LIBRARIES_ZED ${CUDA_npp_LIBRARY} ${CUDA_npps_LIBRARY} ${CUDA_nppi_LIBRARY})
Expand All @@ -114,11 +147,11 @@ set(LINK_LIBRARIES
${OpenCV_LIBS}
${PCL_LIBRARIES})

add_library(ZEDWrapper src/zed_wrapper_nodelet.cpp)
add_library(ZEDWrapper ${TOOLS_SRC} ${NODELET_SRC})
target_link_libraries(ZEDWrapper ${LINK_LIBRARIES})
add_dependencies(ZEDWrapper ${PROJECT_NAME}_gencfg)

add_executable(zed_wrapper_node src/zed_wrapper_node.cpp)
add_executable(zed_wrapper_node ${NODE_SRC})
target_link_libraries(zed_wrapper_node ZEDWrapper ${LINK_LIBRARIES})
add_dependencies(zed_wrapper_node ${PROJECT_NAME}_gencfg)

Expand Down
2 changes: 1 addition & 1 deletion LICENSE
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
Copyright (c) 2017, Stereolabs
Copyright (c) 2018, Stereolabs
All rights reserved.

Redistribution and use in source and binary forms, with or without
Expand Down
5 changes: 3 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# 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, odometry information and supports the use of multiple ZED cameras.
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.

## Getting started

Expand All @@ -25,7 +25,8 @@ The zed_ros_wrapper is a catkin package. It depends on the following ROS package
- roscpp
- rosconsole
- sensor_msgs
- opencv
- stereo_msgs
- opencv3
- image_transport
- dynamic_reconfigure
- urdf
Expand Down
1 change: 1 addition & 0 deletions cfg/Zed.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -9,5 +9,6 @@ gen.add("confidence", int_t, 0, "Confidence threshold, the lower the better", 80
gen.add("exposure", int_t, 1, "Exposure value when manual controlled", 100, 0, 100);
gen.add("gain", int_t, 2, "Gain value when manual controlled", 50, 0, 100);
gen.add("auto_exposure", bool_t, 3, "Enable/Disable auto control of exposure and gain", True);
gen.add("mat_resize_factor", double_t, 4, "Image/Measures resize factor", 1.0, 0.1, 1.0);

exit(gen.generate(PACKAGE, "zed_wrapper", "Zed"))
2 changes: 1 addition & 1 deletion launch/display.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<!--
Copyright (c) 2017, STEREOLABS.
Copyright (c) 2018, STEREOLABS.

All rights reserved.

Expand Down
2 changes: 1 addition & 1 deletion launch/display_zedm.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<!--
Copyright (c) 2017, STEREOLABS.
Copyright (c) 2018, STEREOLABS.

All rights reserved.

Expand Down
32 changes: 23 additions & 9 deletions launch/zed.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<!--
Copyright (c) 2017, STEREOLABS.
Copyright (c) 2018, STEREOLABS.

All rights reserved.

Expand All @@ -17,18 +17,32 @@ THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<launch>
<!-- Odometry coordinate frame -->
<arg name="odometry_frame" default="map" />
<arg name="camera_model" default="0" /> <!-- 0=ZED, 1=ZEDM-->
<arg name="serial_number" default="0" />
<arg name="svo_file" default="" /> <!-- <arg name="svo_file" default="path/to/svo/file.svo"> -->

<arg name="camera_model" default="1" /> <!-- 0=ZED, 1=ZEDM-->
<arg name="serial_number" default="0" />
<arg name="verbose" default="true" />
<arg name="resolution" default="2" /> <!--0=RESOLUTION_HD2K, 1=RESOLUTION_HD1080, 2=RESOLUTION_HD720, 3=RESOLUTION_VGA -->
<arg name="frame_rate" default="30" />
<!-- RESOLUTION_HD2K -> 2208*1242, available framerates: 15 fps.
RESOLUTION_HD1080 -> 1920*1080, available framerates: 15, 30 fps.
RESOLUTION_HD720 -> 1280*720, available framerates: 15, 30, 60 fps.
RESOLUTION_VGA -> 672*376, available framerates: 15, 30, 60, 100 fps. -->

<!-- Coordinate frame -->
<arg name="pose_frame" default="map" />
<arg name="odometry_frame" default="odom" />

<group ns="zed">
<include file="$(find zed_wrapper)/launch/zed_camera.launch">
<!-- compliant mode for rviz -->
<arg name="odometry_frame" value="$(arg odometry_frame)" />
<arg name="svo_file" value="$(arg svo_file)" />
<arg name="pose_frame" value="$(arg pose_frame)" />
<arg name="odometry_frame" value="$(arg odometry_frame)" />
<arg name="camera_model" value="$(arg camera_model)" />
<arg name="serial_number" default="$(arg serial_number)" />
<arg name="serial_number" default="$(arg serial_number)" />
<arg name="resolution" default="$(arg resolution)" />
<arg name="frame_rate" default="$(arg frame_rate)" />
<arg name="verbose" default="$(arg verbose)" />
</include>
</group>

</launch>
103 changes: 73 additions & 30 deletions launch/zed_camera.launch
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<!--
Copyright (c) 2017, STEREOLABS.
Copyright (c) 2018, STEREOLABS.

All rights reserved.

Expand All @@ -21,41 +21,68 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
<arg name="svo_file" default="" /><!-- <arg name="svo_file" default="path/to/svo/file.svo"> -->
<arg name="zed_id" default="0" />
<!-- If a ZED SN is given, zed_id is ignored and the wrapper will specifically look for the ZED with the corresponding serial number -->
<arg name="serial_number" default="0" />
<arg name="serial_number" default="0" />
<arg name="verbose" default="true" />

<arg name="resolution" default="2" /> <!--0=RESOLUTION_HD2K, 1=RESOLUTION_HD1080, 2=RESOLUTION_HD720, 3=RESOLUTION_VGA -->
<arg name="frame_rate" default="30" />
<!-- RESOLUTION_HD2K -> 2208*1242, available framerates: 15 fps.
RESOLUTION_HD1080 -> 1920*1080, available framerates: 15, 30 fps.
RESOLUTION_HD720 -> 1280*720, available framerates: 15, 30, 60 fps.
RESOLUTION_VGA -> 672*376, available framerates: 15, 30, 60, 100 fps. -->

<!-- GPU ID-->
<arg name="gpu_id" default="-1" />

<!-- Definition coordinate frames -->
<arg name="publish_tf" default="true" />
<arg name="odometry_frame" default="odom" />
<arg name="base_frame" default="zed_center" />
<arg name="camera_frame" default="zed_left_camera" />
<arg name="depth_frame" default="zed_depth_camera" />
<arg name="publish_tf" default="true" />
<arg name="pose_frame" default="map" />
<arg name="odometry_frame" default="odom" />
<arg name="base_frame" default="zed_camera_center" />
<arg name="left_camera_frame" default="zed_left_camera_frame" />
<arg name="left_camera_optical_frame" default="zed_left_camera_optical_frame" />
<arg name="right_camera_frame" default="zed_right_camera_frame" />
<arg name="right_camera_optical_frame" default="zed_right_camera_optical_frame" />
<arg name="imu_frame" default="imu_link" /> <!-- only used with ZED M -->

<arg name="initial_pose" default="[0.0,0.0,0.0, 0.0,0.0,0.0]" /> <!-- X, Y, Z, (meter) R, P, Y, (radians)-->

<!-- Publish urdf zed -->
<arg name="publish_urdf" default="true" />

<arg name="rgb_topic" default="rgb/image_rect_color" />
<arg name="rgb_info_topic" default="rgb/camera_info" />
<arg name="depth_topic" default="depth/depth_registered" />

<node name="zed_wrapper_node" pkg="zed_wrapper" type="zed_wrapper_node" output="screen" required="true"><!-- launch-prefix="valgrind" -->
<node name="zed_wrapper_node" pkg="zed_wrapper" type="zed_wrapper_node" output="screen" required="true"><!-- launch-prefix="valgrind" -->

<param name="camera_model" value="$(arg camera_model)" />

<param name="camera_model" value="$(arg camera_model)" />
<!-- publish odometry frame -->
<!-- publish pose frame -->
<param name="publish_tf" value="$(arg publish_tf)" />

<!-- Configuration frame camera -->
<param name="odometry_frame" value="$(arg odometry_frame)" />
<param name="base_frame" value="$(arg base_frame)" />
<param name="camera_frame" value="$(arg camera_frame)" />
<param name="depth_frame" value="$(arg depth_frame)" />
<param name="pose_frame" value="$(arg pose_frame)" />
<param name="odometry_frame" value="$(arg odometry_frame)" />
<param name="base_frame" value="$(arg base_frame)" />
<param name="left_camera_frame" value="$(arg left_camera_frame)" />
<param name="left_camera_optical_frame" value="$(arg left_camera_optical_frame)" />
<param name="right_camera_frame" value="$(arg right_camera_frame)" />
<param name="right_camera_optical_frame" value="$(arg right_camera_optical_frame)" />

<!-- SVO file path -->
<param name="svo_filepath" value="$(arg svo_file)" />

<!-- ZED parameters -->
<param name="zed_id" value="$(arg zed_id)" />
<param name="serial_number" value="$(arg serial_number)" />
<param name="serial_number" value="$(arg serial_number)" />

<param name="resolution" value="2" />
<param name="resolution" value="$(arg resolution)" />
<param name="verbose" value="$(arg verbose)" />
<param name="mat_resize_factor" value="1.0" />
<param name="quality" value="1" />
<param name="sensing_mode" value="0" />
<param name="frame_rate" value="60" />
<param name="frame_rate" value="$(arg frame_rate)" />
<param name="odometry_db" value="" />
<param name="openni_depth_mode" value="0" />
<param name="gpu_id" value="$(arg gpu_id)" />
Expand All @@ -64,29 +91,45 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
<param name="exposure" value="100" />
<param name="auto_exposure" value="true" />
<param name="depth_stabilization" value="1" />
<param name="pose_smoothing" value="false" />
<param name="spatial_memory" value="true" />

<rosparam param="initial_tracking_pose" subst_value="True">$(arg initial_pose)</rosparam>

<!-- ROS topic names -->
<param name="rgb_topic" value="rgb/image_rect_color" />
<param name="rgb_raw_topic" value="rgb/image_raw_color" />
<param name="rgb_cam_info_topic" value="rgb/camera_info" />
<param name="rgb_topic" value="$(arg rgb_topic)" />
<param name="rgb_raw_topic" value="rgb/image_raw_color" />
<param name="rgb_cam_info_topic" value="$(arg rgb_info_topic)" />
<param name="rgb_cam_info_raw_topic" value="rgb/camera_info_raw" />

<param name="left_topic" value="left/image_rect_color" />
<param name="left_raw_topic" value="left/image_raw_color" />
<param name="left_cam_info_topic" value="left/camera_info" />
<param name="left_topic" value="left/image_rect_color" />
<param name="left_raw_topic" value="left/image_raw_color" />
<param name="left_cam_info_topic" value="left/camera_info" />
<param name="left_cam_info_raw_topic" value="left/camera_info_raw" />

<param name="right_topic" value="right/image_rect_color" />
<param name="right_raw_topic" value="right/image_raw_color" />
<param name="right_cam_info_topic" value="right/camera_info" />
<param name="right_topic" value="right/image_rect_color" />
<param name="right_raw_topic" value="right/image_raw_color" />
<param name="right_cam_info_topic" value="right/camera_info" />
<param name="right_cam_info_raw_topic" value="right/camera_info_raw" />

<param name="depth_topic" value="depth/depth_registered" />
<param name="depth_cam_info_topic" value="depth/camera_info" />
<param name="depth_topic" value="$(arg depth_topic)" />
<param name="depth_cam_info_topic" value="depth/camera_info" />

<param name="point_cloud_topic" value="point_cloud/cloud_registered" />

<param name="disparity_topic" value="disparity/disparity_image" />
<param name="confidence_img_topic" value="confidence/confidence_image" />
<param name="confidence_map_topic" value="confidence/confidence_map" />

<param name="pose_topic" value="map" />
<param name="odometry_topic" value="odom" />

<param name="init_odom_with_imu" value="true" /> <!-- only used with ZED mini -->

<param name="point_cloud_topic" value="point_cloud/cloud_registered" />
<param name="imu_topic" value="imu/data" /> <!-- only used with ZED M -->
<param name="imu_topic_raw" value="imu/data_raw" /> <!-- only used with ZED M -->

<param name="odometry_topic" value="odom" />
<param name="imu_pub_rate" value="500.0" /> <!-- only used with ZED M -->

</node>

Expand Down
Loading