rgbd_relay.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, 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:
64  {}
65 
66  virtual ~RGBDRelay()
67  {
68  }
69 
70 private:
71  virtual void onInit()
72  {
75 
76  pnh.param("compress", compress_, compress_);
77  pnh.param("uncompress", uncompress_, uncompress_);
78 
79  rgbdImageSub_ = nh.subscribe("rgbd_image", 1, &RGBDRelay::callback, this);
80  rgbdImagePub_ = nh.advertise<rtabmap_msgs::RGBDImage>(nh.resolveName("rgbd_image") + "_relay", 1);
81  }
82 
83  void callback(const rtabmap_msgs::RGBDImageConstPtr& input)
84  {
86  {
87  if(!compress_ && !uncompress_)
88  {
89  //just republish it
90  rgbdImagePub_.publish(input);
91  return;
92  }
93 
94  rtabmap_msgs::RGBDImage output;
95  output.header = input->header;
96  output.rgb_camera_info = input->rgb_camera_info;
97  output.depth_camera_info = input->depth_camera_info;
98  output.key_points = input->key_points;
99  output.points = input->points;
100  output.descriptors = input->descriptors;
101  output.global_descriptor = input->global_descriptor;
102 
103  rtabmap::StereoCameraModel stereoModel = rtabmap_conversions::stereoCameraModelFromROS(input->rgb_camera_info, input->depth_camera_info, rtabmap::Transform::getIdentity());
104 
105  if(compress_)
106  {
107  if(!input->rgb_compressed.data.empty())
108  {
109  // already compressed, just copy pointer
110  output.rgb_compressed = input->rgb_compressed;
111  }
112  else if(!input->rgb.data.empty())
113  {
114 #ifdef CV_BRIDGE_HYDRO
115  ROS_ERROR("Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
116 #else
117  cv_bridge::CvImageConstPtr rgb = cv_bridge::toCvShare(input->rgb, input);
118  rgb->toCompressedImageMsg(output.rgb_compressed, cv_bridge::JPG);
119 #endif
120  }
121 
122  if(!input->depth_compressed.data.empty())
123  {
124  // already compressed, just copy pointer
125  output.depth_compressed = input->depth_compressed;
126  }
127  else if(!input->depth.data.empty())
128  {
129  if(stereoModel.isValidForProjection())
130  {
131  // right stereo image
132  cv_bridge::CvImageConstPtr imageRightPtr = cv_bridge::toCvShare(input->depth, input);
133  imageRightPtr->toCompressedImageMsg(output.depth_compressed, cv_bridge::JPG);
134  }
135  else
136  {
137  // depth image
138  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(input->depth, input);
139  output.depth_compressed.data = rtabmap::compressImage(imageDepthPtr->image, ".png");
140  output.depth_compressed.format = "png";
141  }
142  }
143  }
144  if(uncompress_)
145  {
146  if(!input->rgb.data.empty())
147  {
148  // already raw, just copy pointer
149  output.rgb = input->rgb;
150  }
151  if(!input->rgb_compressed.data.empty())
152  {
153 #ifdef CV_BRIDGE_HYDRO
154  ROS_ERROR("Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
155 #else
156  cv_bridge::toCvCopy(input->rgb_compressed)->toImageMsg(output.rgb);
157 #endif
158  }
159 
160  if(!input->depth.data.empty())
161  {
162  // already raw, just copy pointer
163  output.depth = input->depth;
164  }
165  else if(input->depth_compressed.format.compare("jpg")==0)
166  {
167  // right stereo image
168 #ifdef CV_BRIDGE_HYDRO
169  ROS_ERROR("Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
170 #else
171  cv_bridge::toCvCopy(input->depth_compressed)->toImageMsg(output.depth);
172 #endif
173  }
174  else
175  {
176  // depth image
177  cv_bridge::CvImagePtr ptr = boost::make_shared<cv_bridge::CvImage>();
178  ptr->header = input->depth_compressed.header;
179  ptr->image = rtabmap::uncompressImage(input->depth_compressed.data);
180  ROS_ASSERT(ptr->image.empty() || ptr->image.type() == CV_32FC1 || ptr->image.type() == CV_16UC1);
181  ptr->encoding = ptr->image.empty()?"":ptr->image.type() == CV_32FC1?sensor_msgs::image_encodings::TYPE_32FC1:sensor_msgs::image_encodings::TYPE_16UC1;
182  ptr->toImageMsg(output.depth);
183  }
184  }
185 
186  rgbdImagePub_.publish(output);
187  }
188  }
189 
190 private:
191 
192  bool compress_;
196 };
197 
199 }
200 
rtabmap::uncompressImage
cv::Mat RTABMAP_CORE_EXPORT uncompressImage(const cv::Mat &bytes)
rtabmap::StereoCameraModel
rtabmap_util::RGBDRelay::~RGBDRelay
virtual ~RGBDRelay()
Definition: rgbd_relay.cpp:66
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
rtabmap_util::RGBDRelay::onInit
virtual void onInit()
Definition: rgbd_relay.cpp:71
boost::shared_ptr
ros.h
rtabmap::Transform::getIdentity
static Transform getIdentity()
Compression.h
rtabmap_util::RGBDRelay::compress_
bool compress_
Definition: rgbd_relay.cpp:192
rtabmap::compressImage
std::vector< unsigned char > RTABMAP_CORE_EXPORT compressImage(const cv::Mat &image, const std::string &format=".png")
rtabmap_util
Definition: MapsManager.h:49
rtabmap_util::RGBDRelay::uncompress_
bool uncompress_
Definition: rgbd_relay.cpp:193
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
sensor_msgs::image_encodings::TYPE_16UC1
const std::string TYPE_16UC1
rtabmap_util::RGBDRelay::callback
void callback(const rtabmap_msgs::RGBDImageConstPtr &input)
Definition: rgbd_relay.cpp:83
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
rtabmap_conversions::stereoCameraModelFromROS
rtabmap::StereoCameraModel stereoCameraModelFromROS(const sensor_msgs::CameraInfo &leftCamInfo, const sensor_msgs::CameraInfo &rightCamInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity(), const rtabmap::Transform &stereoTransform=rtabmap::Transform())
subscriber_filter.h
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
subscriber.h
rtabmap_util::RGBDRelay::RGBDRelay
RGBDRelay()
Definition: rgbd_relay.cpp:61
rtabmap::StereoCameraModel::isValidForProjection
bool isValidForProjection() const
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())
rtabmap_util::RGBDRelay
Definition: rgbd_relay.cpp:58
rtabmap_util::RGBDRelay::rgbdImagePub_
ros::Publisher rgbdImagePub_
Definition: rgbd_relay.cpp:195
image_transport.h
exact_time.h
rtabmap_util::PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(rtabmap_util::DisparityToDepth, nodelet::Nodelet)
nodelet::Nodelet
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
nodelet.h
cv_bridge.h
ROS_ERROR
#define ROS_ERROR(...)
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
approximate_time.h
false
#define false
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
UConversion.h
ROS_ASSERT
#define ROS_ASSERT(cond)
MsgConversion.h
cv_bridge::JPG
JPG
rtabmap_util::RGBDRelay::rgbdImageSub_
ros::Subscriber rgbdImageSub_
Definition: rgbd_relay.cpp:194
ros::NodeHandle
ros::Subscriber


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