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::CallbackQueueInterface & | getMTCallbackQueue () const |
ros::NodeHandle & | getMTNodeHandle () const |
ros::NodeHandle & | getMTPrivateNodeHandle () const |
const V_string & | getMyArgv () const |
const std::string & | getName () const |
ros::NodeHandle & | getNodeHandle () const |
ros::NodeHandle & | getPrivateNodeHandle () const |
const M_string & | getRemappingArgs () const |
ros::CallbackQueueInterface & | getSTCallbackQueue () const |
std::string | getSuffixedName (const std::string &suffix) const |
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.
|
private |
Definition at line 440 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 438 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 436 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 439 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 437 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 435 of file point_cloud_aggregator.cpp.
|
inline |
Definition at line 66 of file point_cloud_aggregator.cpp.
|
inlinevirtual |
Definition at line 79 of file point_cloud_aggregator.cpp.
|
inlineprivate |
Definition at line 219 of file point_cloud_aggregator.cpp.
|
inlineprivate |
Definition at line 208 of file point_cloud_aggregator.cpp.
|
inlineprivate |
Definition at line 195 of file point_cloud_aggregator.cpp.
|
inlineprivate |
Definition at line 228 of file point_cloud_aggregator.cpp.
|
inlineprivatevirtual |
Implements nodelet::Nodelet.
Definition at line 97 of file point_cloud_aggregator.cpp.
|
inlineprivate |
Definition at line 413 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 446 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 444 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 442 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 433 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 452 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 447 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 448 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 449 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 450 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 445 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 443 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 441 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 455 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 454 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 458 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 456 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 432 of file point_cloud_aggregator.cpp.
|
private |
Definition at line 457 of file point_cloud_aggregator.cpp.