rgbd_split.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2022, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <ros/ros.h>
30 #include <nodelet/nodelet.h>
31 
32 #include <sensor_msgs/Image.h>
33 #include <sensor_msgs/CompressedImage.h>
35 #include <sensor_msgs/CameraInfo.h>
36 
39 
43 
44 #include <cv_bridge/cv_bridge.h>
45 #include <opencv2/highgui/highgui.hpp>
46 
47 #include <boost/thread.hpp>
48 
49 #include "rtabmap_msgs/RGBDImage.h"
51 
54 
55 namespace rtabmap_util
56 {
57 
59 {
60 public:
62  {}
63 
64  virtual ~RGBDSplit()
65  {
66  }
67 
68 private:
69  virtual void onInit()
70  {
73 
74  ros::NodeHandle rgb_nh(nh, nh.resolveName("rgbd_image") + "/rgb");
75  ros::NodeHandle depth_nh(nh, nh.resolveName("rgbd_image") + "/depth");
76  image_transport::ImageTransport rgb_it(rgb_nh);
77  image_transport::ImageTransport depth_it(depth_nh);
78 
79  rgbPub_ = rgb_it.advertiseCamera("image", 1);
80  depthPub_ = depth_it.advertiseCamera("image", 1);
81 
82  rgbdImageSub_ = nh.subscribe("rgbd_image", 1, &RGBDSplit::callback, this);
83  }
84 
85  void callback(const rtabmap_msgs::RGBDImageConstPtr& input)
86  {
88  {
89  sensor_msgs::Image outputImage;
90  sensor_msgs::CameraInfo outputCameraInfo;
91  outputImage.header = outputCameraInfo.header = input->header;
92  outputCameraInfo = input->rgb_camera_info;
93 
94  if(!input->rgb.data.empty())
95  {
96  // already raw, just copy pointer
97  outputImage = input->rgb;
98  }
99  else if(!input->rgb_compressed.data.empty())
100  {
101 #ifdef CV_BRIDGE_HYDRO
102  ROS_ERROR("Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
103 #else
104  cv_bridge::toCvCopy(input->rgb_compressed)->toImageMsg(outputImage);
105 #endif
106  }
107  rgbPub_.publish(outputImage, outputCameraInfo);
108  }
109 
111  {
112  sensor_msgs::Image outputImage;
113  sensor_msgs::CameraInfo outputCameraInfo;
114  outputCameraInfo = input->depth_camera_info;
115 
116  if(!input->depth.data.empty())
117  {
118  // already raw, just copy pointer
119  outputImage = input->depth;
120  }
121  else if(!input->depth_compressed.data.empty())
122  {
123 #ifdef CV_BRIDGE_HYDRO
124  ROS_ERROR("Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
125 #else
126  cv_bridge::toCvCopy(input->depth_compressed)->toImageMsg(outputImage);
127 #endif
128  }
129  outputImage.header = outputCameraInfo.header = input->header;
130  depthPub_.publish(outputImage, outputCameraInfo);
131  }
132  }
133 
134 private:
138 };
139 
141 }
142 
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
image_transport::ImageTransport
rtabmap_util::RGBDSplit::rgbdImageSub_
ros::Subscriber rgbdImageSub_
Definition: rgbd_split.cpp:135
image_transport::CameraPublisher::getNumSubscribers
uint32_t getNumSubscribers() const
rtabmap_util::RGBDSplit::RGBDSplit
RGBDSplit()
Definition: rgbd_split.cpp:61
ros.h
Compression.h
rtabmap_util::RGBDSplit::~RGBDSplit
virtual ~RGBDSplit()
Definition: rgbd_split.cpp:64
image_transport::CameraPublisher::publish
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
yaml_to_camera_info.Image
Image
Definition: yaml_to_camera_info.py:61
rtabmap_util
Definition: MapsManager.h:49
image_transport::ImageTransport::advertiseCamera
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
subscriber_filter.h
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
rtabmap_util::RGBDSplit::rgbPub_
image_transport::CameraPublisher rgbPub_
Definition: rgbd_split.cpp:136
subscriber.h
rtabmap_util::RGBDSplit::onInit
virtual void onInit()
Definition: rgbd_split.cpp:69
image_transport::CameraPublisher
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
image_transport.h
exact_time.h
rtabmap_util::RGBDSplit::callback
void callback(const rtabmap_msgs::RGBDImageConstPtr &input)
Definition: rgbd_split.cpp:85
rtabmap_util::RGBDSplit::depthPub_
image_transport::CameraPublisher depthPub_
Definition: rgbd_split.cpp:137
rtabmap_util::PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(rtabmap_util::DisparityToDepth, nodelet::Nodelet)
nodelet::Nodelet
nodelet.h
cv_bridge.h
ROS_ERROR
#define ROS_ERROR(...)
rtabmap_util::RGBDSplit
Definition: rgbd_split.cpp:58
class_list_macros.hpp
approximate_time.h
UConversion.h
MsgConversion.h
ros::NodeHandle
ros::Subscriber


rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50