rgbd_throttle.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <memory>
4 #include <mutex>
5 #include <optional>
6 
10 
11 namespace camera_throttle
12 {
13 
50 {
51  public: RgbdCameraThrottleNodelet() = default;
52  public: ~RgbdCameraThrottleNodelet() override {};
53 
54  protected: void onInit() override;
55 
56  protected: virtual void cb(const sensor_msgs::ImageConstPtr& rgbImg, const sensor_msgs::CameraInfoConstPtr& rgbIinfo, const sensor_msgs::ImageConstPtr& depthImg, const sensor_msgs::CameraInfoConstPtr& depthInfo);
57  protected: virtual void cbPcl(const sensor_msgs::ImageConstPtr& rgbImg, const sensor_msgs::CameraInfoConstPtr& rgbInfo, const sensor_msgs::ImageConstPtr& depthImg, const sensor_msgs::CameraInfoConstPtr& depthInfo, const sensor_msgs::PointCloud2ConstPtr& pcl);
58 
59  protected: virtual void onFirstConnect();
60  protected: virtual void onLastDisconnect();
61 
68  protected: std::unique_ptr<RgbdImageTransport> subTransport;
69  protected: std::unique_ptr<RgbdImageTransport> pubTransport;
70  protected: std::optional<RgbdCameraSubscriber> sub;
72  protected: std::optional<ros::Rate> rate;
73  protected: std::optional<std::string> rgbFrameId;
74  protected: std::optional<std::string> depthFrameId;
75  protected: size_t queueSize {10};
76  protected: ros::Time lastUpdate;
77  protected: std::string subRGBBaseName;
78  protected: std::string pubRGBBaseName;
79  protected: std::string subDepthBaseName;
80  protected: std::string pubDepthBaseName;
81  protected: bool subscribePcl;
82 
83  protected: std::mutex publishersMutex;
84 
86  private: void info_connect_cb(const ros::SingleSubscriberPublisher&);
89 };
90 
91 }
camera_throttle::RgbdCameraThrottleNodelet::subRgbNh
ros::NodeHandle subRgbNh
Definition: rgbd_throttle.h:62
camera_throttle::RgbdCameraThrottleNodelet::RgbdCameraThrottleNodelet
RgbdCameraThrottleNodelet()=default
camera_throttle::RgbdCameraThrottleNodelet::depthFrameId
std::optional< std::string > depthFrameId
Definition: rgbd_throttle.h:74
camera_throttle::RgbdCameraThrottleNodelet::cbPcl
virtual void cbPcl(const sensor_msgs::ImageConstPtr &rgbImg, const sensor_msgs::CameraInfoConstPtr &rgbInfo, const sensor_msgs::ImageConstPtr &depthImg, const sensor_msgs::CameraInfoConstPtr &depthInfo, const sensor_msgs::PointCloud2ConstPtr &pcl)
Definition: rgbd_throttle.cpp:124
camera_throttle::RgbdCameraThrottleNodelet::pubDepthNh
ros::NodeHandle pubDepthNh
Definition: rgbd_throttle.h:66
camera_throttle::RgbdCameraThrottleNodelet::subDepthBaseName
std::string subDepthBaseName
Definition: rgbd_throttle.h:79
rgbd_camera_publisher.h
camera_throttle::RgbdCameraThrottleNodelet::lastUpdate
ros::Time lastUpdate
Definition: rgbd_throttle.h:76
camera_throttle::RgbdCameraThrottleNodelet::sub
std::optional< RgbdCameraSubscriber > sub
Definition: rgbd_throttle.h:70
camera_throttle::RgbdCameraThrottleNodelet::pubPclNh
ros::NodeHandle pubPclNh
Definition: rgbd_throttle.h:67
camera_throttle::RgbdCameraThrottleNodelet
Definition: rgbd_throttle.h:49
camera_throttle::RgbdCameraThrottleNodelet::img_disconnect_cb
void img_disconnect_cb(const image_transport::SingleSubscriberPublisher &)
Definition: rgbd_throttle.cpp:190
camera_throttle::RgbdCameraThrottleNodelet::onFirstConnect
virtual void onFirstConnect()
Definition: rgbd_throttle.cpp:204
camera_throttle::RgbdCameraThrottleNodelet::publishersMutex
std::mutex publishersMutex
Definition: rgbd_throttle.h:83
camera_throttle::RgbdCameraThrottleNodelet::subRGBBaseName
std::string subRGBBaseName
Definition: rgbd_throttle.h:77
camera_throttle::RgbdCameraThrottleNodelet::rgbFrameId
std::optional< std::string > rgbFrameId
Definition: rgbd_throttle.h:73
ros::SingleSubscriberPublisher
camera_throttle::RgbdCameraThrottleNodelet::onInit
void onInit() override
Definition: rgbd_throttle.cpp:8
camera_throttle::RgbdCameraThrottleNodelet::img_connect_cb
void img_connect_cb(const image_transport::SingleSubscriberPublisher &)
Definition: rgbd_throttle.cpp:176
camera_throttle::RgbdCameraThrottleNodelet::cb
virtual void cb(const sensor_msgs::ImageConstPtr &rgbImg, const sensor_msgs::CameraInfoConstPtr &rgbIinfo, const sensor_msgs::ImageConstPtr &depthImg, const sensor_msgs::CameraInfoConstPtr &depthInfo)
Definition: rgbd_throttle.cpp:72
camera_throttle::RgbdCameraThrottleNodelet::pubRgbNh
ros::NodeHandle pubRgbNh
Definition: rgbd_throttle.h:65
camera_throttle::RgbdCameraThrottleNodelet::info_disconnect_cb
void info_disconnect_cb(const ros::SingleSubscriberPublisher &)
Definition: rgbd_throttle.cpp:197
camera_throttle::RgbdCameraThrottleNodelet::rate
std::optional< ros::Rate > rate
Definition: rgbd_throttle.h:72
camera_throttle::RgbdCameraThrottleNodelet::pubRGBBaseName
std::string pubRGBBaseName
Definition: rgbd_throttle.h:78
camera_throttle::RgbdCameraThrottleNodelet::subPclNh
ros::NodeHandle subPclNh
Definition: rgbd_throttle.h:64
camera_throttle::RgbdCameraThrottleNodelet::queueSize
size_t queueSize
Definition: rgbd_throttle.h:75
camera_throttle::RgbdCameraThrottleNodelet::subscribePcl
bool subscribePcl
Definition: rgbd_throttle.h:81
camera_throttle::RgbdCameraThrottleNodelet::subTransport
std::unique_ptr< RgbdImageTransport > subTransport
Definition: rgbd_throttle.h:68
image_transport::SingleSubscriberPublisher
camera_throttle::RgbdCameraThrottleNodelet::info_connect_cb
void info_connect_cb(const ros::SingleSubscriberPublisher &)
Definition: rgbd_throttle.cpp:183
camera_throttle::RgbdCameraThrottleNodelet::subDepthNh
ros::NodeHandle subDepthNh
Definition: rgbd_throttle.h:63
ros::Time
camera_throttle::RgbdCameraThrottleNodelet::pub
RgbdCameraPublisher pub
Definition: rgbd_throttle.h:71
camera_throttle
Definition: camera_throttle.h:11
camera_throttle::RgbdCameraThrottleNodelet::~RgbdCameraThrottleNodelet
~RgbdCameraThrottleNodelet() override
Definition: rgbd_throttle.h:52
cras::Nodelet
camera_throttle::RgbdCameraThrottleNodelet::pubTransport
std::unique_ptr< RgbdImageTransport > pubTransport
Definition: rgbd_throttle.h:69
rgbd_camera_subscriber.h
camera_throttle::RgbdCameraPublisher
Manages advertisements for publishing RGBD camera images.
Definition: rgbd_camera_publisher.h:30
camera_throttle::RgbdCameraThrottleNodelet::pubDepthBaseName
std::string pubDepthBaseName
Definition: rgbd_throttle.h:80
ros::NodeHandle
nodelet_utils.hpp
camera_throttle::RgbdCameraThrottleNodelet::onLastDisconnect
virtual void onLastDisconnect()
Definition: rgbd_throttle.cpp:223


camera_throttle
Author(s): Martin Pecka
autogenerated on Sat Dec 14 2024 03:51:15