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_ros/RGBDImage.h"
51 
54 
55 namespace rtabmap_ros
56 {
57 
59 {
60 public:
64  {}
65 
66  virtual ~RGBDRelay()
67  {
68  }
69 
70 private:
71  virtual void onInit()
72  {
75 
76  int queueSize = 10;
77  bool approxSync = true;
78  pnh.param("queue_size", queueSize, queueSize);
79  pnh.param("compress", compress_, compress_);
80  pnh.param("uncompress", uncompress_, uncompress_);
81 
82  NODELET_INFO("%s: queue_size = %d", getName().c_str(), queueSize);
83 
84  rgbdImageSub_ = nh.subscribe("rgbd_image", 1, &RGBDRelay::callback, this);
85  rgbdImagePub_ = nh.advertise<rtabmap_ros::RGBDImage>(nh.resolveName("rgbd_image") + "_relay", 1);
86  }
87 
88  void callback(const rtabmap_ros::RGBDImageConstPtr& input)
89  {
91  {
92  if(!compress_ && !uncompress_)
93  {
94  //just republish it
95  rgbdImagePub_.publish(input);
96  return;
97  }
98 
99  rtabmap_ros::RGBDImage output;
100  output.header = input->header;
101  output.rgb_camera_info = input->rgb_camera_info;
102  output.depth_camera_info = input->depth_camera_info;
103  output.key_points = input->key_points;
104  output.points = input->points;
105  output.descriptors = input->descriptors;
106  output.global_descriptor = input->global_descriptor;
107 
108  rtabmap::StereoCameraModel stereoModel = stereoCameraModelFromROS(input->rgb_camera_info, input->depth_camera_info, rtabmap::Transform::getIdentity());
109 
110  if(compress_)
111  {
112  if(!input->rgb_compressed.data.empty())
113  {
114  // already compressed, just copy pointer
115  output.rgb_compressed = input->rgb_compressed;
116  }
117  else if(!input->rgb.data.empty())
118  {
119 #ifdef CV_BRIDGE_HYDRO
120  ROS_ERROR("Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
121 #else
122  cv_bridge::CvImageConstPtr rgb = cv_bridge::toCvShare(input->rgb, input);
123  rgb->toCompressedImageMsg(output.rgb_compressed, cv_bridge::JPG);
124 #endif
125  }
126 
127  if(!input->depth_compressed.data.empty())
128  {
129  // already compressed, just copy pointer
130  output.depth_compressed = input->depth_compressed;
131  }
132  else if(!input->depth.data.empty())
133  {
134  if(stereoModel.isValidForProjection())
135  {
136  // right stereo image
137  cv_bridge::CvImageConstPtr imageRightPtr = cv_bridge::toCvShare(input->depth, input);
138  imageRightPtr->toCompressedImageMsg(output.depth_compressed, cv_bridge::JPG);
139  }
140  else
141  {
142  // depth image
143  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(input->depth, input);
144  output.depth_compressed.data = rtabmap::compressImage(imageDepthPtr->image, ".png");
145  output.depth_compressed.format = "png";
146  }
147  }
148  }
149  if(uncompress_)
150  {
151  if(!input->rgb.data.empty())
152  {
153  // already raw, just copy pointer
154  output.rgb = input->rgb;
155  }
156  if(!input->rgb_compressed.data.empty())
157  {
158 #ifdef CV_BRIDGE_HYDRO
159  ROS_ERROR("Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
160 #else
161  cv_bridge::toCvCopy(input->rgb_compressed)->toImageMsg(output.rgb);
162 #endif
163  }
164 
165  if(!input->depth.data.empty())
166  {
167  // already raw, just copy pointer
168  output.depth = input->depth;
169  }
170  else if(input->depth_compressed.format.compare("jpg")==0)
171  {
172  // right stereo image
173 #ifdef CV_BRIDGE_HYDRO
174  ROS_ERROR("Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
175 #else
176  cv_bridge::toCvCopy(input->depth_compressed)->toImageMsg(output.depth);
177 #endif
178  }
179  else
180  {
181  // depth image
182  cv_bridge::CvImagePtr ptr = boost::make_shared<cv_bridge::CvImage>();
183  ptr->header = input->depth_compressed.header;
184  ptr->image = rtabmap::uncompressImage(input->depth_compressed.data);
185  ROS_ASSERT(ptr->image.empty() || ptr->image.type() == CV_32FC1 || ptr->image.type() == CV_16UC1);
186  ptr->encoding = ptr->image.empty()?"":ptr->image.type() == CV_32FC1?sensor_msgs::image_encodings::TYPE_32FC1:sensor_msgs::image_encodings::TYPE_16UC1;
187  ptr->toImageMsg(output.depth);
188  }
189  }
190 
191  rgbdImagePub_.publish(output);
192  }
193  }
194 
195 private:
196 
197  bool compress_;
201 };
202 
204 }
205 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
bool isValidForProjection() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static Transform getIdentity()
ros::NodeHandle & getNodeHandle() const
ros::NodeHandle & getPrivateNodeHandle() const
void callback(const rtabmap_ros::RGBDImageConstPtr &input)
Definition: rgbd_relay.cpp:88
std::vector< unsigned char > RTABMAP_EXP compressImage(const cv::Mat &image, const std::string &format=".png")
const std::string & getName() const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
const std::string TYPE_32FC1
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
const std::string TYPE_16UC1
std::string resolveName(const std::string &name, bool remap=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher rgbdImagePub_
Definition: rgbd_relay.cpp:200
#define false
virtual void onInit()
Definition: rgbd_relay.cpp:71
#define NODELET_INFO(...)
ros::Subscriber rgbdImageSub_
Definition: rgbd_relay.cpp:199
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())
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
#define ROS_ASSERT(cond)
uint32_t getNumSubscribers() const
#define ROS_ERROR(...)
cv::Mat RTABMAP_EXP uncompressImage(const cv::Mat &bytes)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40