32 #include <sensor_msgs/Image.h> 33 #include <sensor_msgs/CompressedImage.h> 35 #include <sensor_msgs/CameraInfo.h> 45 #include <opencv2/highgui/highgui.hpp> 47 #include <boost/thread.hpp> 49 #include "rtabmap_ros/RGBDImage.h" 75 pnh.
param(
"queue_size", queueSize, queueSize);
84 rgbPub_ = rgb_it.advertiseCamera(
"image", 1);
90 void callback(
const rtabmap_ros::RGBDImageConstPtr& input)
95 sensor_msgs::CameraInfo outputCameraInfo;
96 outputImage.header = outputCameraInfo.header = input->header;
97 outputCameraInfo = input->rgb_camera_info;
99 if(!input->rgb.data.empty())
102 outputImage = input->rgb;
104 else if(!input->rgb_compressed.data.empty())
106 #ifdef CV_BRIDGE_HYDRO 107 ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
118 sensor_msgs::CameraInfo outputCameraInfo;
119 outputCameraInfo = input->depth_camera_info;
121 if(!input->depth.data.empty())
124 outputImage = input->depth;
126 else if(!input->depth_compressed.data.empty())
128 #ifdef CV_BRIDGE_HYDRO 129 ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
134 outputImage.header = outputCameraInfo.header = input->header;
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
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 ¶m_name, T ¶m_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_
void callback(const rtabmap_ros::RGBDImageConstPtr &input)
ros::Subscriber rgbdImageSub_
#define NODELET_INFO(...)
image_transport::CameraPublisher rgbPub_
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)