43 #include <sensor_msgs/CameraInfo.h> 44 #include <sensor_msgs/Image.h> 47 #include <QtCore/QStringList> 52 CameraROS(
bool subscribeDepth, QObject * parent = 0);
66 const sensor_msgs::ImageConstPtr& rgbMsg,
67 const sensor_msgs::ImageConstPtr& depthMsg,
68 const sensor_msgs::CameraInfoConstPtr& cameraInfoMsg);
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncPolicy
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
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_
QStringList subscribedTopics() const
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
CameraROS(bool subscribeDepth, QObject *parent=0)
image_transport::Subscriber imageSub_
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncPolicy