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_ros/RGBDImage.h"
51 
54 
55 namespace rtabmap_ros
56 {
57 
59 {
60 public:
62  {}
63 
64  virtual ~RGBDSplit()
65  {
66  }
67 
68 private:
69  virtual void onInit()
70  {
73 
74  int queueSize = 10;
75  pnh.param("queue_size", queueSize, queueSize);
76 
77  NODELET_INFO("%s: queue_size = %d", getName().c_str(), queueSize);
78 
79  ros::NodeHandle rgb_nh(nh, nh.resolveName("rgbd_image") + "/rgb");
80  ros::NodeHandle depth_nh(nh, nh.resolveName("rgbd_image") + "/depth");
81  image_transport::ImageTransport rgb_it(rgb_nh);
82  image_transport::ImageTransport depth_it(depth_nh);
83 
84  rgbPub_ = rgb_it.advertiseCamera("image", 1);
85  depthPub_ = depth_it.advertiseCamera("image", 1);
86 
87  rgbdImageSub_ = nh.subscribe("rgbd_image", 1, &RGBDSplit::callback, this);
88  }
89 
90  void callback(const rtabmap_ros::RGBDImageConstPtr& input)
91  {
93  {
94  sensor_msgs::Image outputImage;
95  sensor_msgs::CameraInfo outputCameraInfo;
96  outputImage.header = outputCameraInfo.header = input->header;
97  outputCameraInfo = input->rgb_camera_info;
98 
99  if(!input->rgb.data.empty())
100  {
101  // already raw, just copy pointer
102  outputImage = input->rgb;
103  }
104  else if(!input->rgb_compressed.data.empty())
105  {
106 #ifdef CV_BRIDGE_HYDRO
107  ROS_ERROR("Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
108 #else
109  cv_bridge::toCvCopy(input->rgb_compressed)->toImageMsg(outputImage);
110 #endif
111  }
112  rgbPub_.publish(outputImage, outputCameraInfo);
113  }
114 
116  {
117  sensor_msgs::Image outputImage;
118  sensor_msgs::CameraInfo outputCameraInfo;
119  outputCameraInfo = input->depth_camera_info;
120 
121  if(!input->depth.data.empty())
122  {
123  // already raw, just copy pointer
124  outputImage = input->depth;
125  }
126  else if(!input->depth_compressed.data.empty())
127  {
128 #ifdef CV_BRIDGE_HYDRO
129  ROS_ERROR("Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
130 #else
131  cv_bridge::toCvCopy(input->depth_compressed)->toImageMsg(outputImage);
132 #endif
133  }
134  outputImage.header = outputCameraInfo.header = input->header;
135  depthPub_.publish(outputImage, outputCameraInfo);
136  }
137  }
138 
139 private:
143 };
144 
146 }
147 
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::NodeHandle & getNodeHandle() const
virtual void onInit()
Definition: rgbd_split.cpp:69
ros::NodeHandle & getPrivateNodeHandle() const
const std::string & getName() const
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
uint32_t getNumSubscribers() const
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string resolveName(const std::string &name, bool remap=true) const
image_transport::CameraPublisher depthPub_
Definition: rgbd_split.cpp:142
void callback(const rtabmap_ros::RGBDImageConstPtr &input)
Definition: rgbd_split.cpp:90
ros::Subscriber rgbdImageSub_
Definition: rgbd_split.cpp:140
#define NODELET_INFO(...)
image_transport::CameraPublisher rgbPub_
Definition: rgbd_split.cpp:141
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
#define ROS_ERROR(...)


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