Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
rtabmap_ros::PointCloudAssembler Class Reference
Inheritance diagram for rtabmap_ros::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_ros::OdomInfo > syncInfoPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, nav_msgs::Odometry > syncPolicy
 

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_ros::OdomInfoConstPtr &odomInfoMsg)
 
virtual void onInit ()
 
void warningLoop (const std::string &subscribedTopicsMsg)
 

Private Attributes

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_
 
int maxClouds_
 
int noiseMinNeighbors_
 
double noiseRadius_
 
double rangeMax_
 
double rangeMin_
 
int skipClouds_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > syncCloudSub_
 
message_filters::Subscriber< rtabmap_ros::OdomInfo > syncOdomInfoSub_
 
message_filters::Subscriber< nav_msgs::Odometry > syncOdomSub_
 
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::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

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 65 of file point_cloud_assembler.cpp.

Member Typedef Documentation

typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, nav_msgs::Odometry, rtabmap_ros::OdomInfo> rtabmap_ros::PointCloudAssembler::syncInfoPolicy
private

Definition at line 397 of file point_cloud_assembler.cpp.

typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, nav_msgs::Odometry> rtabmap_ros::PointCloudAssembler::syncPolicy
private

Definition at line 396 of file point_cloud_assembler.cpp.

Constructor & Destructor Documentation

rtabmap_ros::PointCloudAssembler::PointCloudAssembler ( )
inline

Definition at line 68 of file point_cloud_assembler.cpp.

virtual rtabmap_ros::PointCloudAssembler::~PointCloudAssembler ( )
inlinevirtual

Definition at line 88 of file point_cloud_assembler.cpp.

Member Function Documentation

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

Definition at line 228 of file point_cloud_assembler.cpp.

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

Definition at line 184 of file point_cloud_assembler.cpp.

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

Definition at line 202 of file point_cloud_assembler.cpp.

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

Implements nodelet::Nodelet.

Definition at line 102 of file point_cloud_assembler.cpp.

void rtabmap_ros::PointCloudAssembler::warningLoop ( const std::string &  subscribedTopicsMsg)
inlineprivate

Definition at line 372 of file point_cloud_assembler.cpp.

Member Data Documentation

double rtabmap_ros::PointCloudAssembler::assemblingTime_
private

Definition at line 408 of file point_cloud_assembler.cpp.

bool rtabmap_ros::PointCloudAssembler::callbackCalled_
private

Definition at line 391 of file point_cloud_assembler.cpp.

bool rtabmap_ros::PointCloudAssembler::circularBuffer_
private

Definition at line 407 of file point_cloud_assembler.cpp.

ros::Publisher rtabmap_ros::PointCloudAssembler::cloudPub_
private

Definition at line 394 of file point_cloud_assembler.cpp.

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

Definition at line 419 of file point_cloud_assembler.cpp.

int rtabmap_ros::PointCloudAssembler::cloudsSkipped_
private

Definition at line 406 of file point_cloud_assembler.cpp.

ros::Subscriber rtabmap_ros::PointCloudAssembler::cloudSub_
private

Definition at line 393 of file point_cloud_assembler.cpp.

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

Definition at line 399 of file point_cloud_assembler.cpp.

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

Definition at line 398 of file point_cloud_assembler.cpp.

std::string rtabmap_ros::PointCloudAssembler::fixedFrameId_
private

Definition at line 415 of file point_cloud_assembler.cpp.

std::string rtabmap_ros::PointCloudAssembler::frameId_
private

Definition at line 416 of file point_cloud_assembler.cpp.

int rtabmap_ros::PointCloudAssembler::maxClouds_
private

Definition at line 404 of file point_cloud_assembler.cpp.

int rtabmap_ros::PointCloudAssembler::noiseMinNeighbors_
private

Definition at line 414 of file point_cloud_assembler.cpp.

double rtabmap_ros::PointCloudAssembler::noiseRadius_
private

Definition at line 413 of file point_cloud_assembler.cpp.

double rtabmap_ros::PointCloudAssembler::rangeMax_
private

Definition at line 411 of file point_cloud_assembler.cpp.

double rtabmap_ros::PointCloudAssembler::rangeMin_
private

Definition at line 410 of file point_cloud_assembler.cpp.

int rtabmap_ros::PointCloudAssembler::skipClouds_
private

Definition at line 405 of file point_cloud_assembler.cpp.

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

Definition at line 400 of file point_cloud_assembler.cpp.

message_filters::Subscriber<rtabmap_ros::OdomInfo> rtabmap_ros::PointCloudAssembler::syncOdomInfoSub_
private

Definition at line 402 of file point_cloud_assembler.cpp.

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

Definition at line 401 of file point_cloud_assembler.cpp.

tf::TransformListener rtabmap_ros::PointCloudAssembler::tfListener_
private

Definition at line 417 of file point_cloud_assembler.cpp.

double rtabmap_ros::PointCloudAssembler::voxelSize_
private

Definition at line 412 of file point_cloud_assembler.cpp.

double rtabmap_ros::PointCloudAssembler::waitForTransformDuration_
private

Definition at line 409 of file point_cloud_assembler.cpp.

boost::thread* rtabmap_ros::PointCloudAssembler::warningThread_
private

Definition at line 390 of file point_cloud_assembler.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