Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
rtabmap_ros::DataThrottleNodelet Class Reference
Inheritance diagram for rtabmap_ros::DataThrottleNodelet:
Inheritance graph
[legend]

Public Member Functions

 DataThrottleNodelet ()
 
virtual ~DataThrottleNodelet ()
 
- 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 ()
 
virtual ~Nodelet ()
 

Private Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyApproxSyncPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncPolicy
 

Private Member Functions

void callback (const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &imageDepth, const sensor_msgs::CameraInfoConstPtr &camInfo)
 
virtual void onInit ()
 

Private Attributes

message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
 
int decimation_
 
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
 
image_transport::SubscriberFilter image_depth_sub_
 
image_transport::SubscriberFilter image_sub_
 
image_transport::Publisher imageDepthPub_
 
image_transport::Publisher imagePub_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > info_sub_
 
ros::Publisher infoPub_
 
ros::Time last_update_
 
double rate_
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::stringgetName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

Definition at line 49 of file data_throttle.cpp.

Member Typedef Documentation

◆ MyApproxSyncPolicy

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> rtabmap_ros::DataThrottleNodelet::MyApproxSyncPolicy
private

Definition at line 231 of file data_throttle.cpp.

◆ MyExactSyncPolicy

typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> rtabmap_ros::DataThrottleNodelet::MyExactSyncPolicy
private

Definition at line 233 of file data_throttle.cpp.

Constructor & Destructor Documentation

◆ DataThrottleNodelet()

rtabmap_ros::DataThrottleNodelet::DataThrottleNodelet ( )
inline

Definition at line 53 of file data_throttle.cpp.

◆ ~DataThrottleNodelet()

virtual rtabmap_ros::DataThrottleNodelet::~DataThrottleNodelet ( )
inlinevirtual

Definition at line 61 of file data_throttle.cpp.

Member Function Documentation

◆ callback()

void rtabmap_ros::DataThrottleNodelet::callback ( const sensor_msgs::ImageConstPtr &  image,
const sensor_msgs::ImageConstPtr &  imageDepth,
const sensor_msgs::CameraInfoConstPtr &  camInfo 
)
inlineprivate

Definition at line 131 of file data_throttle.cpp.

◆ onInit()

virtual void rtabmap_ros::DataThrottleNodelet::onInit ( )
inlineprivatevirtual

Implements nodelet::Nodelet.

Definition at line 76 of file data_throttle.cpp.

Member Data Documentation

◆ approxSync_

message_filters::Synchronizer<MyApproxSyncPolicy>* rtabmap_ros::DataThrottleNodelet::approxSync_
private

Definition at line 232 of file data_throttle.cpp.

◆ decimation_

int rtabmap_ros::DataThrottleNodelet::decimation_
private

Definition at line 236 of file data_throttle.cpp.

◆ exactSync_

message_filters::Synchronizer<MyExactSyncPolicy>* rtabmap_ros::DataThrottleNodelet::exactSync_
private

Definition at line 234 of file data_throttle.cpp.

◆ image_depth_sub_

image_transport::SubscriberFilter rtabmap_ros::DataThrottleNodelet::image_depth_sub_
private

Definition at line 228 of file data_throttle.cpp.

◆ image_sub_

image_transport::SubscriberFilter rtabmap_ros::DataThrottleNodelet::image_sub_
private

Definition at line 227 of file data_throttle.cpp.

◆ imageDepthPub_

image_transport::Publisher rtabmap_ros::DataThrottleNodelet::imageDepthPub_
private

Definition at line 224 of file data_throttle.cpp.

◆ imagePub_

image_transport::Publisher rtabmap_ros::DataThrottleNodelet::imagePub_
private

Definition at line 223 of file data_throttle.cpp.

◆ info_sub_

message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::DataThrottleNodelet::info_sub_
private

Definition at line 229 of file data_throttle.cpp.

◆ infoPub_

ros::Publisher rtabmap_ros::DataThrottleNodelet::infoPub_
private

Definition at line 225 of file data_throttle.cpp.

◆ last_update_

ros::Time rtabmap_ros::DataThrottleNodelet::last_update_
private

Definition at line 74 of file data_throttle.cpp.

◆ rate_

double rtabmap_ros::DataThrottleNodelet::rate_
private

Definition at line 75 of file data_throttle.cpp.


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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40