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

Public Member Functions

 PointCloudAssembler ()
 
virtual ~PointCloudAssembler ()
 
- 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::ExactTime< sensor_msgs::PointCloud2, nav_msgs::Odometry, rtabmap_msgs::OdomInfo > syncInfoPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, nav_msgs::OdometrysyncPolicy
 

Private Member Functions

void callbackCloud (const sensor_msgs::PointCloud2ConstPtr &cloudMsg)
 
void callbackCloudOdom (const sensor_msgs::PointCloud2ConstPtr &cloudMsg, const nav_msgs::OdometryConstPtr &odomMsg)
 
void callbackCloudOdomInfo (const sensor_msgs::PointCloud2ConstPtr &cloudMsg, const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)
 
virtual void onInit ()
 
sensor_msgs::PointCloud2 removeField (const sensor_msgs::PointCloud2 &input, const std::string &field)
 
void warningLoop (const std::string &subscribedTopicsMsg)
 

Private Attributes

double angularUpdate_
 
double assemblingTime_
 
bool callbackCalled_
 
bool circularBuffer_
 
ros::Publisher cloudPub_
 
std::list< pcl::PCLPointCloud2::Ptr > clouds_
 
int cloudsSkipped_
 
ros::Subscriber cloudSub_
 
message_filters::Synchronizer< syncInfoPolicy > * exactInfoSync_
 
message_filters::Synchronizer< syncPolicy > * exactSync_
 
std::string fixedFrameId_
 
std::string frameId_
 
double linearUpdate_
 
int maxClouds_
 
int noiseMinNeighbors_
 
double noiseRadius_
 
rtabmap::Transform previousPose_
 
double rangeMax_
 
double rangeMin_
 
bool removeZ_
 
int skipClouds_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > syncCloudSub_
 
message_filters::Subscriber< rtabmap_msgs::OdomInfo > syncOdomInfoSub_
 
message_filters::Subscriber< nav_msgs::OdometrysyncOdomSub_
 
tf::TransformListener tfListener_
 
double voxelSize_
 
double waitForTransformDuration_
 
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

This nodelet can assemble a number of clouds (max_clouds) coming from the same sensor, taking into account the displacement of the robot based on fixed_frame_id, then publish the resulting cloud. If fixed_frame_id is set to "" (empty), the nodelet will subscribe to an odom topic that should have the exact same stamp than to input cloud. The output cloud has the same stamp and frame than the last assembled cloud.

Definition at line 67 of file point_cloud_assembler.cpp.

Member Typedef Documentation

◆ syncInfoPolicy

Definition at line 562 of file point_cloud_assembler.cpp.

◆ syncPolicy

Definition at line 561 of file point_cloud_assembler.cpp.

Constructor & Destructor Documentation

◆ PointCloudAssembler()

rtabmap_util::PointCloudAssembler::PointCloudAssembler ( )
inline

Definition at line 70 of file point_cloud_assembler.cpp.

◆ ~PointCloudAssembler()

virtual rtabmap_util::PointCloudAssembler::~PointCloudAssembler ( )
inlinevirtual

Definition at line 93 of file point_cloud_assembler.cpp.

Member Function Documentation

◆ callbackCloud()

void rtabmap_util::PointCloudAssembler::callbackCloud ( const sensor_msgs::PointCloud2ConstPtr &  cloudMsg)
inlineprivate

Definition at line 303 of file point_cloud_assembler.cpp.

◆ callbackCloudOdom()

void rtabmap_util::PointCloudAssembler::callbackCloudOdom ( const sensor_msgs::PointCloud2ConstPtr &  cloudMsg,
const nav_msgs::OdometryConstPtr &  odomMsg 
)
inlineprivate

Definition at line 215 of file point_cloud_assembler.cpp.

◆ callbackCloudOdomInfo()

void rtabmap_util::PointCloudAssembler::callbackCloudOdomInfo ( const sensor_msgs::PointCloud2ConstPtr &  cloudMsg,
const nav_msgs::OdometryConstPtr &  odomMsg,
const rtabmap_msgs::OdomInfoConstPtr &  odomInfoMsg 
)
inlineprivate

Definition at line 233 of file point_cloud_assembler.cpp.

◆ onInit()

virtual void rtabmap_util::PointCloudAssembler::onInit ( )
inlineprivatevirtual

Implements nodelet::Nodelet.

Definition at line 107 of file point_cloud_assembler.cpp.

◆ removeField()

sensor_msgs::PointCloud2 rtabmap_util::PointCloudAssembler::removeField ( const sensor_msgs::PointCloud2 &  input,
const std::string field 
)
inlineprivate

Definition at line 259 of file point_cloud_assembler.cpp.

◆ warningLoop()

void rtabmap_util::PointCloudAssembler::warningLoop ( const std::string subscribedTopicsMsg)
inlineprivate

Definition at line 537 of file point_cloud_assembler.cpp.

Member Data Documentation

◆ angularUpdate_

double rtabmap_util::PointCloudAssembler::angularUpdate_
private

Definition at line 574 of file point_cloud_assembler.cpp.

◆ assemblingTime_

double rtabmap_util::PointCloudAssembler::assemblingTime_
private

Definition at line 575 of file point_cloud_assembler.cpp.

◆ callbackCalled_

bool rtabmap_util::PointCloudAssembler::callbackCalled_
private

Definition at line 556 of file point_cloud_assembler.cpp.

◆ circularBuffer_

bool rtabmap_util::PointCloudAssembler::circularBuffer_
private

Definition at line 572 of file point_cloud_assembler.cpp.

◆ cloudPub_

ros::Publisher rtabmap_util::PointCloudAssembler::cloudPub_
private

Definition at line 559 of file point_cloud_assembler.cpp.

◆ clouds_

std::list<pcl::PCLPointCloud2::Ptr> rtabmap_util::PointCloudAssembler::clouds_
private

Definition at line 588 of file point_cloud_assembler.cpp.

◆ cloudsSkipped_

int rtabmap_util::PointCloudAssembler::cloudsSkipped_
private

Definition at line 571 of file point_cloud_assembler.cpp.

◆ cloudSub_

ros::Subscriber rtabmap_util::PointCloudAssembler::cloudSub_
private

Definition at line 558 of file point_cloud_assembler.cpp.

◆ exactInfoSync_

message_filters::Synchronizer<syncInfoPolicy>* rtabmap_util::PointCloudAssembler::exactInfoSync_
private

Definition at line 564 of file point_cloud_assembler.cpp.

◆ exactSync_

message_filters::Synchronizer<syncPolicy>* rtabmap_util::PointCloudAssembler::exactSync_
private

Definition at line 563 of file point_cloud_assembler.cpp.

◆ fixedFrameId_

std::string rtabmap_util::PointCloudAssembler::fixedFrameId_
private

Definition at line 583 of file point_cloud_assembler.cpp.

◆ frameId_

std::string rtabmap_util::PointCloudAssembler::frameId_
private

Definition at line 584 of file point_cloud_assembler.cpp.

◆ linearUpdate_

double rtabmap_util::PointCloudAssembler::linearUpdate_
private

Definition at line 573 of file point_cloud_assembler.cpp.

◆ maxClouds_

int rtabmap_util::PointCloudAssembler::maxClouds_
private

Definition at line 569 of file point_cloud_assembler.cpp.

◆ noiseMinNeighbors_

int rtabmap_util::PointCloudAssembler::noiseMinNeighbors_
private

Definition at line 581 of file point_cloud_assembler.cpp.

◆ noiseRadius_

double rtabmap_util::PointCloudAssembler::noiseRadius_
private

Definition at line 580 of file point_cloud_assembler.cpp.

◆ previousPose_

rtabmap::Transform rtabmap_util::PointCloudAssembler::previousPose_
private

Definition at line 586 of file point_cloud_assembler.cpp.

◆ rangeMax_

double rtabmap_util::PointCloudAssembler::rangeMax_
private

Definition at line 578 of file point_cloud_assembler.cpp.

◆ rangeMin_

double rtabmap_util::PointCloudAssembler::rangeMin_
private

Definition at line 577 of file point_cloud_assembler.cpp.

◆ removeZ_

bool rtabmap_util::PointCloudAssembler::removeZ_
private

Definition at line 582 of file point_cloud_assembler.cpp.

◆ skipClouds_

int rtabmap_util::PointCloudAssembler::skipClouds_
private

Definition at line 570 of file point_cloud_assembler.cpp.

◆ syncCloudSub_

message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_util::PointCloudAssembler::syncCloudSub_
private

Definition at line 565 of file point_cloud_assembler.cpp.

◆ syncOdomInfoSub_

message_filters::Subscriber<rtabmap_msgs::OdomInfo> rtabmap_util::PointCloudAssembler::syncOdomInfoSub_
private

Definition at line 567 of file point_cloud_assembler.cpp.

◆ syncOdomSub_

message_filters::Subscriber<nav_msgs::Odometry> rtabmap_util::PointCloudAssembler::syncOdomSub_
private

Definition at line 566 of file point_cloud_assembler.cpp.

◆ tfListener_

tf::TransformListener rtabmap_util::PointCloudAssembler::tfListener_
private

Definition at line 585 of file point_cloud_assembler.cpp.

◆ voxelSize_

double rtabmap_util::PointCloudAssembler::voxelSize_
private

Definition at line 579 of file point_cloud_assembler.cpp.

◆ waitForTransformDuration_

double rtabmap_util::PointCloudAssembler::waitForTransformDuration_
private

Definition at line 576 of file point_cloud_assembler.cpp.

◆ warningThread_

boost::thread* rtabmap_util::PointCloudAssembler::warningThread_
private

Definition at line 555 of file point_cloud_assembler.cpp.


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


rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50