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_
 
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::string & getName () 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 62 of file point_cloud_aggregator.cpp.

Member Typedef Documentation

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

Definition at line 322 of file point_cloud_aggregator.cpp.

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

Definition at line 320 of file point_cloud_aggregator.cpp.

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 318 of file point_cloud_aggregator.cpp.

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

Definition at line 321 of file point_cloud_aggregator.cpp.

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

Definition at line 319 of file point_cloud_aggregator.cpp.

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 317 of file point_cloud_aggregator.cpp.

Constructor & Destructor Documentation

rtabmap_ros::PointCloudAggregator::PointCloudAggregator ( )
inline

Definition at line 65 of file point_cloud_aggregator.cpp.

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

Definition at line 76 of file point_cloud_aggregator.cpp.

Member Function Documentation

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

Definition at line 203 of file point_cloud_aggregator.cpp.

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 192 of file point_cloud_aggregator.cpp.

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 179 of file point_cloud_aggregator.cpp.

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

Definition at line 212 of file point_cloud_aggregator.cpp.

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

Implements nodelet::Nodelet.

Definition at line 94 of file point_cloud_aggregator.cpp.

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

Definition at line 295 of file point_cloud_aggregator.cpp.

Member Data Documentation

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

Definition at line 328 of file point_cloud_aggregator.cpp.

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

Definition at line 326 of file point_cloud_aggregator.cpp.

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

Definition at line 324 of file point_cloud_aggregator.cpp.

bool rtabmap_ros::PointCloudAggregator::callbackCalled_
private

Definition at line 315 of file point_cloud_aggregator.cpp.

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

Definition at line 334 of file point_cloud_aggregator.cpp.

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

Definition at line 329 of file point_cloud_aggregator.cpp.

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

Definition at line 330 of file point_cloud_aggregator.cpp.

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

Definition at line 331 of file point_cloud_aggregator.cpp.

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

Definition at line 332 of file point_cloud_aggregator.cpp.

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

Definition at line 327 of file point_cloud_aggregator.cpp.

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

Definition at line 325 of file point_cloud_aggregator.cpp.

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

Definition at line 323 of file point_cloud_aggregator.cpp.

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

Definition at line 337 of file point_cloud_aggregator.cpp.

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

Definition at line 336 of file point_cloud_aggregator.cpp.

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

Definition at line 338 of file point_cloud_aggregator.cpp.

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

Definition at line 314 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 Mon Dec 14 2020 03:42:19