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

Public Member Functions

 PointCloudAggregator ()
 
virtual ~PointCloudAggregator ()
 
- 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::PointCloud2, sensor_msgs::PointCloud2 > ApproxSync2Policy
 
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ApproxSync3Policy
 
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ApproxSync4Policy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ExactSync2Policy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ExactSync3Policy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > ExactSync4Policy
 

Private Member Functions

void clouds2_callback (const sensor_msgs::PointCloud2ConstPtr &cloudMsg_1, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_2)
 
void clouds3_callback (const sensor_msgs::PointCloud2ConstPtr &cloudMsg_1, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_2, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_3)
 
void clouds4_callback (const sensor_msgs::PointCloud2ConstPtr &cloudMsg_1, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_2, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_3, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_4)
 
void combineClouds (const std::vector< sensor_msgs::PointCloud2ConstPtr > &cloudMsgs)
 
virtual void onInit ()
 
void warningLoop (const std::string &subscribedTopicsMsg, bool approxSync)
 

Private Attributes

message_filters::Synchronizer< ApproxSync2Policy > * approxSync2_
 
message_filters::Synchronizer< ApproxSync3Policy > * approxSync3_
 
message_filters::Synchronizer< ApproxSync4Policy > * approxSync4_
 
bool callbackCalled_
 
ros::Publisher cloudPub_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > cloudSub_1_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > cloudSub_2_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > cloudSub_3_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > cloudSub_4_
 
message_filters::Synchronizer< ExactSync2Policy > * exactSync2_
 
message_filters::Synchronizer< ExactSync3Policy > * exactSync3_
 
message_filters::Synchronizer< ExactSync4Policy > * exactSync4_
 
std::string fixedFrameId_
 
std::string frameId_
 
tf::TransformListener tfListener_
 
double waitForTransformDuration_
 
boost::thread * warningThread_
 
bool xyzOutput_
 

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

Nodelet used to merge point clouds from different sensors into a single assembled cloud. If fixed_frame_id is set and approx_sync is true, the clouds are adjusted to include the displacement of the robot in the output cloud.

Definition at line 63 of file point_cloud_aggregator.cpp.

Member Typedef Documentation

◆ ApproxSync2Policy

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ApproxSync2Policy
private

Definition at line 440 of file point_cloud_aggregator.cpp.

◆ ApproxSync3Policy

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ApproxSync3Policy
private

Definition at line 438 of file point_cloud_aggregator.cpp.

◆ ApproxSync4Policy

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ApproxSync4Policy
private

Definition at line 436 of file point_cloud_aggregator.cpp.

◆ ExactSync2Policy

typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ExactSync2Policy
private

Definition at line 439 of file point_cloud_aggregator.cpp.

◆ ExactSync3Policy

typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ExactSync3Policy
private

Definition at line 437 of file point_cloud_aggregator.cpp.

◆ ExactSync4Policy

typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ExactSync4Policy
private

Definition at line 435 of file point_cloud_aggregator.cpp.

Constructor & Destructor Documentation

◆ PointCloudAggregator()

rtabmap_ros::PointCloudAggregator::PointCloudAggregator ( )
inline

Definition at line 66 of file point_cloud_aggregator.cpp.

◆ ~PointCloudAggregator()

virtual rtabmap_ros::PointCloudAggregator::~PointCloudAggregator ( )
inlinevirtual

Definition at line 79 of file point_cloud_aggregator.cpp.

Member Function Documentation

◆ clouds2_callback()

void rtabmap_ros::PointCloudAggregator::clouds2_callback ( const sensor_msgs::PointCloud2ConstPtr &  cloudMsg_1,
const sensor_msgs::PointCloud2ConstPtr &  cloudMsg_2 
)
inlineprivate

Definition at line 219 of file point_cloud_aggregator.cpp.

◆ clouds3_callback()

void rtabmap_ros::PointCloudAggregator::clouds3_callback ( const sensor_msgs::PointCloud2ConstPtr &  cloudMsg_1,
const sensor_msgs::PointCloud2ConstPtr &  cloudMsg_2,
const sensor_msgs::PointCloud2ConstPtr &  cloudMsg_3 
)
inlineprivate

Definition at line 208 of file point_cloud_aggregator.cpp.

◆ clouds4_callback()

void rtabmap_ros::PointCloudAggregator::clouds4_callback ( const sensor_msgs::PointCloud2ConstPtr &  cloudMsg_1,
const sensor_msgs::PointCloud2ConstPtr &  cloudMsg_2,
const sensor_msgs::PointCloud2ConstPtr &  cloudMsg_3,
const sensor_msgs::PointCloud2ConstPtr &  cloudMsg_4 
)
inlineprivate

Definition at line 195 of file point_cloud_aggregator.cpp.

◆ combineClouds()

void rtabmap_ros::PointCloudAggregator::combineClouds ( const std::vector< sensor_msgs::PointCloud2ConstPtr > &  cloudMsgs)
inlineprivate

Definition at line 228 of file point_cloud_aggregator.cpp.

◆ onInit()

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

Implements nodelet::Nodelet.

Definition at line 97 of file point_cloud_aggregator.cpp.

◆ warningLoop()

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

Definition at line 413 of file point_cloud_aggregator.cpp.

Member Data Documentation

◆ approxSync2_

message_filters::Synchronizer<ApproxSync2Policy>* rtabmap_ros::PointCloudAggregator::approxSync2_
private

Definition at line 446 of file point_cloud_aggregator.cpp.

◆ approxSync3_

message_filters::Synchronizer<ApproxSync3Policy>* rtabmap_ros::PointCloudAggregator::approxSync3_
private

Definition at line 444 of file point_cloud_aggregator.cpp.

◆ approxSync4_

message_filters::Synchronizer<ApproxSync4Policy>* rtabmap_ros::PointCloudAggregator::approxSync4_
private

Definition at line 442 of file point_cloud_aggregator.cpp.

◆ callbackCalled_

bool rtabmap_ros::PointCloudAggregator::callbackCalled_
private

Definition at line 433 of file point_cloud_aggregator.cpp.

◆ cloudPub_

ros::Publisher rtabmap_ros::PointCloudAggregator::cloudPub_
private

Definition at line 452 of file point_cloud_aggregator.cpp.

◆ cloudSub_1_

message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::cloudSub_1_
private

Definition at line 447 of file point_cloud_aggregator.cpp.

◆ cloudSub_2_

message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::cloudSub_2_
private

Definition at line 448 of file point_cloud_aggregator.cpp.

◆ cloudSub_3_

message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::cloudSub_3_
private

Definition at line 449 of file point_cloud_aggregator.cpp.

◆ cloudSub_4_

message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::cloudSub_4_
private

Definition at line 450 of file point_cloud_aggregator.cpp.

◆ exactSync2_

message_filters::Synchronizer<ExactSync2Policy>* rtabmap_ros::PointCloudAggregator::exactSync2_
private

Definition at line 445 of file point_cloud_aggregator.cpp.

◆ exactSync3_

message_filters::Synchronizer<ExactSync3Policy>* rtabmap_ros::PointCloudAggregator::exactSync3_
private

Definition at line 443 of file point_cloud_aggregator.cpp.

◆ exactSync4_

message_filters::Synchronizer<ExactSync4Policy>* rtabmap_ros::PointCloudAggregator::exactSync4_
private

Definition at line 441 of file point_cloud_aggregator.cpp.

◆ fixedFrameId_

std::string rtabmap_ros::PointCloudAggregator::fixedFrameId_
private

Definition at line 455 of file point_cloud_aggregator.cpp.

◆ frameId_

std::string rtabmap_ros::PointCloudAggregator::frameId_
private

Definition at line 454 of file point_cloud_aggregator.cpp.

◆ tfListener_

tf::TransformListener rtabmap_ros::PointCloudAggregator::tfListener_
private

Definition at line 458 of file point_cloud_aggregator.cpp.

◆ waitForTransformDuration_

double rtabmap_ros::PointCloudAggregator::waitForTransformDuration_
private

Definition at line 456 of file point_cloud_aggregator.cpp.

◆ warningThread_

boost::thread* rtabmap_ros::PointCloudAggregator::warningThread_
private

Definition at line 432 of file point_cloud_aggregator.cpp.

◆ xyzOutput_

bool rtabmap_ros::PointCloudAggregator::xyzOutput_
private

Definition at line 457 of file point_cloud_aggregator.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