Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
camera_throttle::RgbdCameraThrottleNodelet Class Reference

#include <rgbd_throttle.h>

Inheritance diagram for camera_throttle::RgbdCameraThrottleNodelet:
Inheritance graph
[legend]

Public Member Functions

 RgbdCameraThrottleNodelet ()=default
 
 ~RgbdCameraThrottleNodelet () override
 
- Public Member Functions inherited from cras::Nodelet
 ~Nodelet () override=default
 
- Public Member Functions inherited from NodeletBase<::nodelet::Nodelet >
 ~NodeletBase () override=default
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
- Public Member Functions inherited from NodeletWithDiagnostics< ::nodelet::Nodelet >
 NodeletWithDiagnostics ()
 
virtual ~NodeletWithDiagnostics ()
 
- Public Member Functions inherited from NodeletWithSharedTfBuffer< ::nodelet::Nodelet >
::cras::NodeletAwareTFBuffergetBuffer () const override
 
::std::shared_ptr<::cras::NodeletAwareTFBuffergetBufferPtr () const
 
 NodeletWithSharedTfBuffer ()
 
void reset () override
 
void setBuffer (const ::std::shared_ptr<::tf2_ros::Buffer > &buffer) override
 
bool usesSharedBuffer () const override
 
 ~NodeletWithSharedTfBuffer () override
 
- Public Member Functions inherited from ThreadNameUpdatingNodelet< ::nodelet::Nodelet >
 ~ThreadNameUpdatingNodelet () override
 
- Public Member Functions inherited from NodeletParamHelper< ::nodelet::Nodelet >
 NodeletParamHelper ()
 
 ~NodeletParamHelper () override
 
- Public Member Functions inherited from cras::ParamHelper
::cras::LogHelperPtr getLogger () const
 
inline ::std::string getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 
ResultType getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 
inline ::std::string getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 
ResultType getParam (const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={}) const
 
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::cras::GetParamAdapter &param, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={}) const
 
 ParamHelper (const ::cras::LogHelperPtr &log)
 
void setLogger (const ::cras::LogHelperPtr &logger)
 
virtual ~ParamHelper ()=default
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 
- Public Member Functions inherited from StatefulNodelet< ::nodelet::Nodelet >
bool ok () const override
 
void requestStop () override
 
void shutdown ()
 
virtual ~StatefulNodelet ()
 
- Public Member Functions inherited from cras::InterruptibleSleepInterface
 InterruptibleSleepInterface ()
 
virtual bool sleep (const ::ros::Duration &duration) const
 
virtual ~InterruptibleSleepInterface ()
 

Protected Member Functions

virtual void cb (const sensor_msgs::ImageConstPtr &rgbImg, const sensor_msgs::CameraInfoConstPtr &rgbIinfo, const sensor_msgs::ImageConstPtr &depthImg, const sensor_msgs::CameraInfoConstPtr &depthInfo)
 
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)
 
virtual void onFirstConnect ()
 
void onInit () override
 
virtual void onLastDisconnect ()
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 
- Protected Member Functions inherited from NodeletWithDiagnostics< ::nodelet::Nodelet >
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::std::string &topic, size_t queueSize, bool latch=false)
 
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (ros::AdvertiseOptions &options)
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,), CRAS_SINGLE_ARG(subscriberNh, diagNh,), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,), CRAS_SINGLE_ARG(subscriberNh, diagNh,), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, ""),), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),), CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,))
 
::std::unique_ptr<::cras::DiagnosedPublisher< T > > createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string &paramNamespace)
 
::std::unique_ptr<::cras::DiagnosedPublisher< T > > createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string &paramNamespace, const ::ros::Rate &defaultRate)
 
::std::unique_ptr<::cras::DiagnosedPublisher< T > > createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string &paramNamespace, const ::ros::Rate &defaultRate, const ::ros::Rate &defaultMinRate, const ::ros::Rate &defaultMaxRate)
 
::ros::NodeHandle getDefaultDiagNh (const ::ros::NodeHandle &pubSubNh, const ::std::string &diagNamespace)
 
::cras::BoundParamHelperPtr getDiagParams (const ::ros::NodeHandle &nh, const ::std::string &diagNamespace, const ::std::string &topic)
 
::cras::DiagnosticUpdatergetDiagUpdater (bool forceNew=false) const
 
void startDiagTimer () const
 
void startDiagTimer (const ::ros::NodeHandle &nh) const
 
void stopDiagTimer () const
 
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::SubscribeOptions &options)
 
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const ::boost::function< void(const ::boost::shared_ptr< Message > &)> &cb, ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< C > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< C >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, const ::boost::function< void(C)> &cb, ::ros::VoidConstPtr obj={}, ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={})
 
- Protected Member Functions inherited from cras::TimeJumpResettable
void checkTimeJump ()
 
virtual void checkTimeJump (const ::ros::Time &now)
 
void initRos (const ::ros::NodeHandle &pnh) override
 
void startAutoCheckTimeJump ()
 
virtual void startAutoCheckTimeJump (const ::ros::WallRate &rate)
 
virtual void stopAutoCheckTimeJump ()
 
 TimeJumpResettable (const ::cras::LogHelperPtr &log)
 
 ~TimeJumpResettable () override
 
- Protected Member Functions inherited from cras::Resettable
 Resettable (const ::cras::LogHelperPtr &log)
 
virtual ~Resettable ()
 
- Protected Member Functions inherited from ThreadNameUpdatingNodelet< ::nodelet::Nodelet >
void updateThreadName () const
 
- Protected Member Functions inherited from NodeletParamHelper< ::nodelet::Nodelet >
inline ::std::string getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
 
ResultType getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 
inline ::std::string getParam (const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
 
ResultType getParam (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< const char * > &defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
 
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ::cras::optional< ResultType > &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 
inline ::cras::GetParamResult<::std::string > getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const char *defaultValue, const ::std::string &unit="", const ::cras::GetParamOptions<::std::string > &options={})
 
inline ::cras::GetParamResult< ResultType > getParamVerbose (const ::ros::NodeHandle &node, const ::std::string &name, const ResultType &defaultValue=ResultType(), const ::std::string &unit="", const ::cras::GetParamOptions< ResultType, ParamServerType > &options={})
 
::cras::BoundParamHelperPtr params (const ::ros::NodeHandle &node, const ::std::string &ns="") const
 
::cras::BoundParamHelperPtr paramsForNodeHandle (const ::ros::NodeHandle &node) const
 
::cras::BoundParamHelperPtr privateParams (const ::std::string &ns="") const
 
::cras::BoundParamHelperPtr publicParams (const ::std::string &ns="") const
 

Protected Attributes

std::optional< std::string > depthFrameId
 
ros::Time lastUpdate
 
RgbdCameraPublisher pub
 
std::string pubDepthBaseName
 
ros::NodeHandle pubDepthNh
 
std::mutex publishersMutex
 
ros::NodeHandle pubPclNh
 
std::string pubRGBBaseName
 
ros::NodeHandle pubRgbNh
 
std::unique_ptr< RgbdImageTransportpubTransport
 
size_t queueSize {10}
 
std::optional< ros::Raterate
 
std::optional< std::string > rgbFrameId
 
std::optional< RgbdCameraSubscribersub
 
std::string subDepthBaseName
 
ros::NodeHandle subDepthNh
 
ros::NodeHandle subPclNh
 
std::string subRGBBaseName
 
ros::NodeHandle subRgbNh
 
bool subscribePcl
 
std::unique_ptr< RgbdImageTransportsubTransport
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 
- Protected Attributes inherited from cras::InterruptibleSleepInterface
::ros::WallDuration pollDuration
 

Private Member Functions

void img_connect_cb (const image_transport::SingleSubscriberPublisher &)
 
void img_disconnect_cb (const image_transport::SingleSubscriberPublisher &)
 
void info_connect_cb (const ros::SingleSubscriberPublisher &)
 
void info_disconnect_cb (const ros::SingleSubscriberPublisher &)
 

Detailed Description

Throttle (or just relay) a RGB and depth camera topic pair (image_raw + camera_info) and possibly pointcloud and publish the output via image_transport.

Parameters: ~rate: If set, the output topic will be rate-limited to this rate (probably a little lower). ~queue_size: Queue size for both subscription and publication. Default is 10. ~sub_rgb_base_name: Base name of the RGB input image. Default is image_raw. ~pub_rgb_base_name: Base name of the RGB output image. Default is whatever is set to ~sub_rgb_base_name. ~sub_depth_base_name: Base name of the depth input image. Default is depth. ~pub_depth_base_name: Base name of the depth output image. Default is whatever is set to ~sub_depth_base_name. ~subscribe_pcl: If true, also the pointcloud will be subscribed and throttled. Default is true. ~fix_rgb_frame_id: If set and nonempty, the RGB images and camera infos will get this frame ID instead of the one they came with. ~fix_depth_frame_id: If set and nonempty, the Depth images and camera infos will get this frame ID instead of the one they came with. ~image_transport: Specifies the image transport to use for subscribing RGB and depth. ~image_transport_rgb: Specifies the image transport to use for subscribing RGB (overrides ~image_transport). ~image_transport_depth: Specifies the image transport to use for subscribing depth (overrides ~image_transport).

Topics: camera_rgb_in: The input RGB camera topics camera_rgb_in/camera_info camera_rgb_in/<~sub_rgb_base_name> camera_depth_in: The input depth camera topics camera_depth_in/camera_info camera_depth_in/<~sub_depth_base_name> points_in: Incoming pointclouds camera_rgb_out: The output RGB camera topics camera_rgb_out/camera_info camera_rgb_out/<~sub_rgb_base_name> camera_rgb_out/<~sub_rgb_base_name>/... - the classic set of topics created by image_transport publisher camera_depth_out: The output depth camera topics camera_depth_out/camera_info camera_depth_out/<~sub_depth_base_name> camera_depth_out/<~sub_depth_base_name>/... - the classic set of topics created by image_transport publisher points_out: Outgoing pointclouds

Definition at line 49 of file rgbd_throttle.h.

Constructor & Destructor Documentation

◆ RgbdCameraThrottleNodelet()

camera_throttle::RgbdCameraThrottleNodelet::RgbdCameraThrottleNodelet ( )
default

◆ ~RgbdCameraThrottleNodelet()

camera_throttle::RgbdCameraThrottleNodelet::~RgbdCameraThrottleNodelet ( )
inlineoverride

Definition at line 52 of file rgbd_throttle.h.

Member Function Documentation

◆ cb()

void camera_throttle::RgbdCameraThrottleNodelet::cb ( const sensor_msgs::ImageConstPtr &  rgbImg,
const sensor_msgs::CameraInfoConstPtr &  rgbIinfo,
const sensor_msgs::ImageConstPtr &  depthImg,
const sensor_msgs::CameraInfoConstPtr &  depthInfo 
)
protectedvirtual

Definition at line 72 of file rgbd_throttle.cpp.

◆ cbPcl()

void camera_throttle::RgbdCameraThrottleNodelet::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 
)
protectedvirtual

Definition at line 124 of file rgbd_throttle.cpp.

◆ img_connect_cb()

void camera_throttle::RgbdCameraThrottleNodelet::img_connect_cb ( const image_transport::SingleSubscriberPublisher status)
private

Definition at line 176 of file rgbd_throttle.cpp.

◆ img_disconnect_cb()

void camera_throttle::RgbdCameraThrottleNodelet::img_disconnect_cb ( const image_transport::SingleSubscriberPublisher status)
private

Definition at line 190 of file rgbd_throttle.cpp.

◆ info_connect_cb()

void camera_throttle::RgbdCameraThrottleNodelet::info_connect_cb ( const ros::SingleSubscriberPublisher status)
private

Definition at line 183 of file rgbd_throttle.cpp.

◆ info_disconnect_cb()

void camera_throttle::RgbdCameraThrottleNodelet::info_disconnect_cb ( const ros::SingleSubscriberPublisher status)
private

Definition at line 197 of file rgbd_throttle.cpp.

◆ onFirstConnect()

void camera_throttle::RgbdCameraThrottleNodelet::onFirstConnect ( )
protectedvirtual

Definition at line 204 of file rgbd_throttle.cpp.

◆ onInit()

void camera_throttle::RgbdCameraThrottleNodelet::onInit ( )
overrideprotectedvirtual

Reimplemented from NodeletBase<::nodelet::Nodelet >.

Definition at line 8 of file rgbd_throttle.cpp.

◆ onLastDisconnect()

void camera_throttle::RgbdCameraThrottleNodelet::onLastDisconnect ( )
protectedvirtual

Definition at line 223 of file rgbd_throttle.cpp.

Member Data Documentation

◆ depthFrameId

std::optional<std::string> camera_throttle::RgbdCameraThrottleNodelet::depthFrameId
protected

Definition at line 74 of file rgbd_throttle.h.

◆ lastUpdate

ros::Time camera_throttle::RgbdCameraThrottleNodelet::lastUpdate
protected

Definition at line 76 of file rgbd_throttle.h.

◆ pub

RgbdCameraPublisher camera_throttle::RgbdCameraThrottleNodelet::pub
protected

Definition at line 71 of file rgbd_throttle.h.

◆ pubDepthBaseName

std::string camera_throttle::RgbdCameraThrottleNodelet::pubDepthBaseName
protected

Definition at line 80 of file rgbd_throttle.h.

◆ pubDepthNh

ros::NodeHandle camera_throttle::RgbdCameraThrottleNodelet::pubDepthNh
protected

Definition at line 66 of file rgbd_throttle.h.

◆ publishersMutex

std::mutex camera_throttle::RgbdCameraThrottleNodelet::publishersMutex
protected

Definition at line 83 of file rgbd_throttle.h.

◆ pubPclNh

ros::NodeHandle camera_throttle::RgbdCameraThrottleNodelet::pubPclNh
protected

Definition at line 67 of file rgbd_throttle.h.

◆ pubRGBBaseName

std::string camera_throttle::RgbdCameraThrottleNodelet::pubRGBBaseName
protected

Definition at line 78 of file rgbd_throttle.h.

◆ pubRgbNh

ros::NodeHandle camera_throttle::RgbdCameraThrottleNodelet::pubRgbNh
protected

Definition at line 65 of file rgbd_throttle.h.

◆ pubTransport

std::unique_ptr<RgbdImageTransport> camera_throttle::RgbdCameraThrottleNodelet::pubTransport
protected

Definition at line 69 of file rgbd_throttle.h.

◆ queueSize

size_t camera_throttle::RgbdCameraThrottleNodelet::queueSize {10}
protected

Definition at line 75 of file rgbd_throttle.h.

◆ rate

std::optional<ros::Rate> camera_throttle::RgbdCameraThrottleNodelet::rate
protected

Definition at line 72 of file rgbd_throttle.h.

◆ rgbFrameId

std::optional<std::string> camera_throttle::RgbdCameraThrottleNodelet::rgbFrameId
protected

Definition at line 73 of file rgbd_throttle.h.

◆ sub

std::optional<RgbdCameraSubscriber> camera_throttle::RgbdCameraThrottleNodelet::sub
protected

Definition at line 70 of file rgbd_throttle.h.

◆ subDepthBaseName

std::string camera_throttle::RgbdCameraThrottleNodelet::subDepthBaseName
protected

Definition at line 79 of file rgbd_throttle.h.

◆ subDepthNh

ros::NodeHandle camera_throttle::RgbdCameraThrottleNodelet::subDepthNh
protected

Definition at line 63 of file rgbd_throttle.h.

◆ subPclNh

ros::NodeHandle camera_throttle::RgbdCameraThrottleNodelet::subPclNh
protected

Definition at line 64 of file rgbd_throttle.h.

◆ subRGBBaseName

std::string camera_throttle::RgbdCameraThrottleNodelet::subRGBBaseName
protected

Definition at line 77 of file rgbd_throttle.h.

◆ subRgbNh

ros::NodeHandle camera_throttle::RgbdCameraThrottleNodelet::subRgbNh
protected

Definition at line 62 of file rgbd_throttle.h.

◆ subscribePcl

bool camera_throttle::RgbdCameraThrottleNodelet::subscribePcl
protected

Definition at line 81 of file rgbd_throttle.h.

◆ subTransport

std::unique_ptr<RgbdImageTransport> camera_throttle::RgbdCameraThrottleNodelet::subTransport
protected

Definition at line 68 of file rgbd_throttle.h.


The documentation for this class was generated from the following files:


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