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"    77                 bool approxSync = 
true;
    78                 pnh.
param(
"queue_size", queueSize, queueSize);
    88         void callback(
const rtabmap_ros::RGBDImageConstPtr& input)
    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;
   112                                 if(!input->rgb_compressed.data.empty())
   115                                         output.rgb_compressed = input->rgb_compressed;
   117                                 else if(!input->rgb.data.empty())
   119 #ifdef CV_BRIDGE_HYDRO   120                                         ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
   127                                 if(!input->depth_compressed.data.empty())
   130                                         output.depth_compressed = input->depth_compressed;
   132                                 else if(!input->depth.data.empty())
   138                                                 imageRightPtr->toCompressedImageMsg(output.depth_compressed, 
cv_bridge::JPG);
   145                                                 output.depth_compressed.format = 
"png";
   151                                 if(!input->rgb.data.empty())
   154                                         output.rgb = input->rgb;
   156                                 if(!input->rgb_compressed.data.empty())
   158 #ifdef CV_BRIDGE_HYDRO   159                                         ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
   165                                 if(!input->depth.data.empty())
   168                                         output.depth = input->depth;
   170                                 else if(input->depth_compressed.format.compare(
"jpg")==0)
   173 #ifdef CV_BRIDGE_HYDRO   174                                         ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
   183                                         ptr->header = input->depth_compressed.header;
   185                                         ROS_ASSERT(ptr->image.empty() || ptr->image.type() == CV_32FC1 || ptr->image.type() == CV_16UC1);
   187                                         ptr->toImageMsg(output.depth);
 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())
ros::NodeHandle & getNodeHandle() const
ros::NodeHandle & getPrivateNodeHandle() const
void callback(const rtabmap_ros::RGBDImageConstPtr &input)
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 ¶m_name, T ¶m_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_
#define NODELET_INFO(...)
ros::Subscriber rgbdImageSub_
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)
uint32_t getNumSubscribers() const
cv::Mat RTABMAP_EXP uncompressImage(const cv::Mat &bytes)