42 #include <sensor_msgs/CameraInfo.h> 43 #include <sensor_msgs/Image.h> 46 #include <QtCore/QStringList> 51 CameraROS(
bool subscribeDepth, QObject * parent = 0);
62 const cv::Mat & depth,
71 const sensor_msgs::ImageConstPtr& rgbMsg,
72 const sensor_msgs::ImageConstPtr& depthMsg,
73 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg);
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MySyncPolicy
void rosDataReceived(const std::string &frameId, const ros::Time &stamp, const cv::Mat &depth, float depthConstant)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
image_transport::SubscriberFilter rgbSub_
void imgDepthReceivedCallback(const sensor_msgs::ImageConstPtr &rgbMsg, const sensor_msgs::ImageConstPtr &depthMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
void imgReceivedCallback(const sensor_msgs::ImageConstPtr &msg)
image_transport::SubscriberFilter depthSub_
message_filters::Synchronizer< MySyncPolicy > * sync_
CameraROS(bool subscribeDepth, QObject *parent=0)
image_transport::Subscriber imageSub_
QStringList subscribedTopics() const