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

Public Member Functions

 RGBDSync ()
 
virtual ~RGBDSync ()
 
- 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 > MyApproxSyncDepthPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > MyExactSyncDepthPolicy
 

Private Member Functions

void callback (const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &depth, const sensor_msgs::CameraInfoConstPtr &cameraInfo)
 
virtual void onInit ()
 
void warningLoop (const std::string &subscribedTopicsMsg, bool approxSync)
 

Private Attributes

message_filters::Synchronizer< MyApproxSyncDepthPolicy > * approxSyncDepth_
 
bool callbackCalled_
 
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoSub_
 
double compressedRate_
 
int decimation_
 
double depthScale_
 
message_filters::Synchronizer< MyExactSyncDepthPolicy > * exactSyncDepth_
 
image_transport::SubscriberFilter imageDepthSub_
 
image_transport::SubscriberFilter imageSub_
 
ros::Time lastCompressedPublished_
 
ros::Publisher rgbdImageCompressedPub_
 
ros::Publisher rgbdImagePub_
 
boost::thread * warningThread_
 

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 59 of file rgbd_sync.cpp.

Member Typedef Documentation

◆ MyApproxSyncDepthPolicy

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> rtabmap_ros::RGBDSync::MyApproxSyncDepthPolicy
private

Definition at line 324 of file rgbd_sync.cpp.

◆ MyExactSyncDepthPolicy

typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> rtabmap_ros::RGBDSync::MyExactSyncDepthPolicy
private

Definition at line 327 of file rgbd_sync.cpp.

Constructor & Destructor Documentation

◆ RGBDSync()

rtabmap_ros::RGBDSync::RGBDSync ( )
inline

Definition at line 62 of file rgbd_sync.cpp.

◆ ~RGBDSync()

virtual rtabmap_ros::RGBDSync::~RGBDSync ( )
inlinevirtual

Definition at line 72 of file rgbd_sync.cpp.

Member Function Documentation

◆ callback()

void rtabmap_ros::RGBDSync::callback ( const sensor_msgs::ImageConstPtr &  image,
const sensor_msgs::ImageConstPtr &  depth,
const sensor_msgs::CameraInfoConstPtr &  cameraInfo 
)
inlineprivate

Definition at line 176 of file rgbd_sync.cpp.

◆ onInit()

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

Implements nodelet::Nodelet.

Definition at line 88 of file rgbd_sync.cpp.

◆ warningLoop()

void rtabmap_ros::RGBDSync::warningLoop ( const std::string subscribedTopicsMsg,
bool  approxSync 
)
inlineprivate

Definition at line 157 of file rgbd_sync.cpp.

Member Data Documentation

◆ approxSyncDepth_

message_filters::Synchronizer<MyApproxSyncDepthPolicy>* rtabmap_ros::RGBDSync::approxSyncDepth_
private

Definition at line 325 of file rgbd_sync.cpp.

◆ callbackCalled_

bool rtabmap_ros::RGBDSync::callbackCalled_
private

Definition at line 313 of file rgbd_sync.cpp.

◆ cameraInfoSub_

message_filters::Subscriber<sensor_msgs::CameraInfo> rtabmap_ros::RGBDSync::cameraInfoSub_
private

Definition at line 322 of file rgbd_sync.cpp.

◆ compressedRate_

double rtabmap_ros::RGBDSync::compressedRate_
private

Definition at line 311 of file rgbd_sync.cpp.

◆ decimation_

int rtabmap_ros::RGBDSync::decimation_
private

Definition at line 310 of file rgbd_sync.cpp.

◆ depthScale_

double rtabmap_ros::RGBDSync::depthScale_
private

Definition at line 309 of file rgbd_sync.cpp.

◆ exactSyncDepth_

message_filters::Synchronizer<MyExactSyncDepthPolicy>* rtabmap_ros::RGBDSync::exactSyncDepth_
private

Definition at line 328 of file rgbd_sync.cpp.

◆ imageDepthSub_

image_transport::SubscriberFilter rtabmap_ros::RGBDSync::imageDepthSub_
private

Definition at line 321 of file rgbd_sync.cpp.

◆ imageSub_

image_transport::SubscriberFilter rtabmap_ros::RGBDSync::imageSub_
private

Definition at line 320 of file rgbd_sync.cpp.

◆ lastCompressedPublished_

ros::Time rtabmap_ros::RGBDSync::lastCompressedPublished_
private

Definition at line 315 of file rgbd_sync.cpp.

◆ rgbdImageCompressedPub_

ros::Publisher rtabmap_ros::RGBDSync::rgbdImageCompressedPub_
private

Definition at line 318 of file rgbd_sync.cpp.

◆ rgbdImagePub_

ros::Publisher rtabmap_ros::RGBDSync::rgbdImagePub_
private

Definition at line 317 of file rgbd_sync.cpp.

◆ warningThread_

boost::thread* rtabmap_ros::RGBDSync::warningThread_
private

Definition at line 312 of file rgbd_sync.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