31 #include <rclcpp/rclcpp.hpp> 39 #include <image_transport/image_transport.hpp> 40 #include <image_transport/subscriber_filter.hpp> 42 #include <sensor_msgs/msg/camera_info.hpp> 43 #include <sensor_msgs/msg/image.hpp> 46 #include <QtCore/QStringList> 51 CameraROS(
bool subscribeDepth, rclcpp::Node * node);
66 const sensor_msgs::msg::Image::ConstSharedPtr rgbMsg,
67 const sensor_msgs::msg::Image::ConstSharedPtr depthMsg,
68 const sensor_msgs::msg::CameraInfo::ConstSharedPtr cameraInfoMsg);
72 rclcpp::executors::SingleThreadedExecutor
executor_;
81 sensor_msgs::msg::Image,
82 sensor_msgs::msg::Image,
87 sensor_msgs::msg::Image,
88 sensor_msgs::msg::Image,
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_
void setupExecutor(std::shared_ptr< rclcpp::Node > node)
QStringList subscribedTopics() const
message_filters::sync_policies::ApproximateTime< sensor_msgs::msg::Image, sensor_msgs::msg::Image, sensor_msgs::msg::CameraInfo > MyApproxSyncPolicy
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
CameraROS(bool subscribeDepth, QObject *parent=0)
image_transport::Subscriber imageSub_
rclcpp::executors::SingleThreadedExecutor executor_
message_filters::sync_policies::ExactTime< sensor_msgs::msg::Image, sensor_msgs::msg::Image, sensor_msgs::msg::CameraInfo > MyExactSyncPolicy
message_filters::Subscriber< sensor_msgs::msg::CameraInfo > cameraInfoSub_