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;
108 if(!input->rgb_compressed.data.empty())
111 output.rgb_compressed = input->rgb_compressed;
113 else if(!input->rgb.data.empty())
115 #ifdef CV_BRIDGE_HYDRO 116 ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
123 if(!input->depth_compressed.data.empty())
126 output.depth_compressed = input->depth_compressed;
128 else if(!input->depth.data.empty())
134 imageRightPtr->toCompressedImageMsg(output.depth_compressed,
cv_bridge::JPG);
141 output.depth_compressed.format =
"png";
147 if(!input->rgb.data.empty())
150 output.rgb = input->rgb;
152 if(!input->rgb_compressed.data.empty())
154 #ifdef CV_BRIDGE_HYDRO 155 ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
161 if(!input->depth.data.empty())
164 output.depth = input->depth;
166 else if(input->depth_compressed.format.compare(
"jpg")==0)
169 #ifdef CV_BRIDGE_HYDRO 170 ROS_ERROR(
"Unsupported compressed image copy, please upgrade at least to ROS Indigo to use this.");
179 ptr->header = input->depth_compressed.header;
181 ROS_ASSERT(ptr->image.empty() || ptr->image.type() == CV_32FC1 || ptr->image.type() == CV_16UC1);
183 ptr->toImageMsg(output.depth);
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
const std::string & getName() const
void callback(const rtabmap_ros::RGBDImageConstPtr &input)
ros::NodeHandle & getPrivateNodeHandle() const
std::vector< unsigned char > RTABMAP_EXP compressImage(const cv::Mat &image, const std::string &format=".png")
bool isValidForProjection() const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string TYPE_32FC1
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
const std::string TYPE_16UC1
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher rgbdImagePub_
ros::NodeHandle & getNodeHandle() const
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
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)
cv::Mat RTABMAP_EXP uncompressImage(const cv::Mat &bytes)