#include <rtabmap_ros/CommonDataSubscriber.h>
#include <rtabmap/utilite/UConversion.h>
#include <rtabmap_ros/MsgConversion.h>
#include <cv_bridge/cv_bridge.h>
Go to the source code of this file.
Namespaces | |
namespace | rtabmap_ros |
Defines | |
#define | IMAGE_CONVERSION() |
#define IMAGE_CONVERSION | ( | ) |
callbackCalled(); \ std::vector<cv_bridge::CvImageConstPtr> imageMsgs(3); \ std::vector<cv_bridge::CvImageConstPtr> depthMsgs(3); \ rtabmap_ros::toCvShare(image1Msg, imageMsgs[0], depthMsgs[0]); \ rtabmap_ros::toCvShare(image2Msg, imageMsgs[1], depthMsgs[1]); \ rtabmap_ros::toCvShare(image3Msg, imageMsgs[2], depthMsgs[2]); \ std::vector<sensor_msgs::CameraInfo> cameraInfoMsgs; \ cameraInfoMsgs.push_back(image1Msg->rgbCameraInfo); \ cameraInfoMsgs.push_back(image2Msg->rgbCameraInfo); \ cameraInfoMsgs.push_back(image3Msg->rgbCameraInfo);
Definition at line 35 of file CommonDataSubscriberRGBD3.cpp.