Skip to content
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
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
9 changes: 0 additions & 9 deletions zed_wrapper/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,6 @@ if ( CMAKE_SYSTEM_NAME2 MATCHES "aarch64" ) # Jetson TX
SET(CUDA_USE_STATIC_CUDA_RUNTIME OFF)
endif()

find_package(OpenCV 3 COMPONENTS core highgui imgproc)
checkPackage("OPENCV_CORE" "OpenCV core not found, install it from the tutorial at:\n https://www.stereolabs.com/documentation/overview/getting-started/getting-started.html")
checkPackage("OPENCV_HIGHGUI" "OpenCV highgui not found, install it from the tutorial at:\n https://www.stereolabs.com/documentation/overview/getting-started/getting-started.html")
checkPackage("OPENCV_IMGPROC" "OpenCV imgproc not found, install it from the tutorial at:\n https://www.stereolabs.com/documentation/overview/getting-started/getting-started.html")

find_package(CUDA)
checkPackage("CUDA" "CUDA not found, install it from:\n https://developer.nvidia.com/cuda-downloads")

Expand Down Expand Up @@ -85,7 +80,6 @@ catkin_package(
rosconsole
sensor_msgs
stereo_msgs
opencv3
image_transport
dynamic_reconfigure
tf2_ros
Expand All @@ -111,14 +105,12 @@ include_directories(
${catkin_INCLUDE_DIRS}
${CUDA_INCLUDE_DIRS}
${ZED_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${CMAKE_CURRENT_SOURCE_DIR}/src/tools/include
${CMAKE_CURRENT_SOURCE_DIR}/src/nodelet/include
)

link_directories(${ZED_LIBRARY_DIR})
link_directories(${CUDA_LIBRARY_DIRS})
link_directories(${OpenCV_LIBRARY_DIRS})

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

Expand All @@ -136,7 +128,6 @@ set(LINK_LIBRARIES
${catkin_LIBRARIES}
${ZED_LIBRARIES}
${CUDA_LIBRARIES} ${CUDA_NPP_LIBRARIES_ZED}
${OpenCV_LIBS}
)

add_library(ZEDWrapper ${TOOLS_SRC} ${NODELET_SRC})
Expand Down
2 changes: 0 additions & 2 deletions zed_wrapper/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,10 @@ 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


Open a terminal and build the package:

cd ~/catkin_ws/src
Expand Down
1 change: 0 additions & 1 deletion zed_wrapper/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
<depend>rosconsole</depend>
<depend>sensor_msgs</depend>
<depend>stereo_msgs</depend>
<depend>opencv3</depend>
<depend>image_transport</depend>
<depend>dynamic_reconfigure</depend>
<depend>nodelet</depend>
Expand Down
24 changes: 9 additions & 15 deletions zed_wrapper/src/nodelet/include/zed_wrapper_nodelet.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,6 @@
#include <zed_wrapper/set_initial_pose.h>
#include <zed_wrapper/reset_odometry.h>

#include <opencv2/core/core.hpp>

#include <mutex>
#include <thread>
#include <condition_variable>
Expand All @@ -69,7 +67,7 @@ namespace zed_wrapper {
* \param frameId : the id of the reference frame of the image
* \param t : the ros::Time to stamp the image
*/
static sensor_msgs::ImagePtr imageToROSmsg(cv::Mat img, const std::string encodingType, std::string frameId, ros::Time t);
static sensor_msgs::ImagePtr imageToROSmsg(sl::Mat img, std::string frameId, ros::Time t);

private:
/* \brief Initialization function called by the Nodelet base class
Expand Down Expand Up @@ -116,25 +114,25 @@ namespace zed_wrapper {
*/
void publishImuFrame(tf2::Transform baseTransform);

/* \brief Publish a cv::Mat image with a ros Publisher
/* \brief Publish a sl::Mat image with a ros Publisher
* \param img : the image to publish
* \param pub_img : the publisher object to use (different image publishers exist)
* \param img_frame_id : the id of the reference frame of the image (different image frames exist)
* \param t : the ros::Time to stamp the image
*/
void publishImage(cv::Mat img, image_transport::Publisher& pubImg, string imgFrameId, ros::Time t);
void publishImage(sl::Mat img, image_transport::Publisher& pubImg, string imgFrameId, ros::Time t);

/* \brief Publish a cv::Mat depth image with a ros Publisher
/* \brief Publish a sl::Mat depth image with a ros Publisher
* \param depth : the depth image to publish
* \param t : the ros::Time to stamp the depth image
*/
void publishDepth(cv::Mat depth, ros::Time t);
void publishDepth(sl::Mat depth, ros::Time t);

/* \brief Publish a cv::Mat confidence image with a ros Publisher
/* \brief Publish a sl::Mat confidence image with a ros Publisher
* \param conf : the confidence image to publish
* \param t : the ros::Time to stamp the depth image
*/
void publishConf(cv::Mat conf, ros::Time t);
void publishConf(sl::Mat conf, ros::Time t);

/* \brief Publish a pointCloud with a ros Publisher
* \param width : the width of the point cloud
Expand All @@ -149,11 +147,11 @@ namespace zed_wrapper {
*/
void publishCamInfo(sensor_msgs::CameraInfoPtr camInfoMsg, ros::Publisher pubCamInfo, ros::Time t);

/* \brief Publish a cv::Mat disparity image with a ros Publisher
/* \brief Publish a sl::Mat disparity image with a ros Publisher
* \param disparity : the disparity image to publish
* \param t : the ros::Time to stamp the depth image
*/
void publishDisparity(cv::Mat disparity, ros::Time t);
void publishDisparity(sl::Mat disparity, ros::Time t);

/* \brief Get the information of the ZED cameras and store them in an information message
* \param zed : the sl::zed::Camera* pointer to an instance
Expand Down Expand Up @@ -344,10 +342,6 @@ namespace zed_wrapper {
int camHeight;
int matWidth;
int matHeight;
cv::Mat leftImRGB;
cv::Mat rightImRGB;
cv::Mat confImRGB;
cv::Mat confMapFloat;

// Mutex
std::mutex dataMutex;
Expand Down
Loading