Fawkes API  Fawkes Development Version
PointCloudDBRetrievePipeline< PointType > Class Template Reference

Point cloud retrieve pipeline. More...

#include <pcl_db_retrieve_pipeline.h>

Inheritance diagram for PointCloudDBRetrievePipeline< PointType >:

Public Member Functions

 PointCloudDBRetrievePipeline (mongo::DBClientBase *mongodb_client, fawkes::Configuration *config, fawkes::Logger *logger, fawkes::tf::Transformer *transformer, typename PointCloudDBPipeline< PointType >::ColorCloudPtr original, typename PointCloudDBPipeline< PointType >::ColorCloudPtr output)
 Constructor. More...
 
virtual ~PointCloudDBRetrievePipeline ()
 Destructor. More...
 
void retrieve (long long timestamp, std::string &database, std::string &collection, std::string &target_frame, long long &actual_time)
 Retrieve point clouds. More...
 
- Public Member Functions inherited from PointCloudDBPipeline< PointType >
 PointCloudDBPipeline (mongo::DBClientBase *mongodb_client, fawkes::Configuration *config, fawkes::Logger *logger, ColorCloudPtr output)
 Constructor. More...
 
virtual ~PointCloudDBPipeline ()
 Destructor. More...
 
ApplicabilityStatus applicable (std::vector< long long > &times, std::string &database, std::string &collection)
 Check if this pipeline instance is suitable for the given times. More...
 

Additional Inherited Members

- Protected Types inherited from PointCloudDBPipeline< PointType >
typedef pcl::PointCloud< PointType > Cloud
 Basic point cloud type. More...
 
typedef pcl::PointXYZRGB ColorPointType
 Colored point type. More...
 
typedef pcl::PointCloud< ColorPointTypeColorCloud
 Type for colored point clouds based on ColorPointType. More...
 
typedef Cloud::Ptr CloudPtr
 Shared pointer to cloud. More...
 
typedef Cloud::ConstPtr CloudConstPtr
 Shared pointer to constant cloud. More...
 
typedef ColorCloud::Ptr ColorCloudPtr
 Shared pointer to colored cloud. More...
 
typedef ColorCloud::ConstPtr ColorCloudConstPtr
 Shared pointer to constant colored cloud. More...
 
- Protected Member Functions inherited from PointCloudDBPipeline< PointType >
void read_gridfs_file (void *dataptr, std::string &database, std::string filename)
 Read a file from MongoDB GridFS. More...
 
std::vector< CloudPtrretrieve_clouds (std::vector< long long > &times, std::vector< long long > &actual_times, std::string &database, std::string &collection)
 Retrieve point clouds from database. More...
 
- Protected Attributes inherited from PointCloudDBPipeline< PointType >
const char * name_
 Name of the pipeline. More...
 
long cfg_pcl_age_tolerance_
 Age tolerance for retrieved point clouds. More...
 
long cfg_transform_range_ [2]
 Transform range start and end times. More...
 
mongo::DBClientBase * mongodb_client_
 MongoDB client to retrieve data. More...
 
fawkes::Loggerlogger_
 Logger for informative messages. More...
 
ColorCloudPtr output_
 The final (colored) output of the pipeline. More...
 

Detailed Description

template<typename PointType>
class PointCloudDBRetrievePipeline< PointType >

Point cloud retrieve pipeline.

This pipeline retrieves a point cloud from the database at a given point in time. The process assums a coordinate frame which is fixed in both, the recorded transforms and the current transform tree. Using this fixed frame it first transforms the point cloud to the fixed frame using the recorded transforms in the database, and then to transform it to the desired sensor frame using the current data.

Author
Tim Niemueller

Definition at line 55 of file pcl_db_retrieve_pipeline.h.

Constructor & Destructor Documentation

◆ PointCloudDBRetrievePipeline()

template<typename PointType>
PointCloudDBRetrievePipeline< PointType >::PointCloudDBRetrievePipeline ( mongo::DBClientBase *  mongodb_client,
fawkes::Configuration config,
fawkes::Logger logger,
fawkes::tf::Transformer transformer,
typename PointCloudDBPipeline< PointType >::ColorCloudPtr  original,
typename PointCloudDBPipeline< PointType >::ColorCloudPtr  output 
)
inline

Constructor.

Parameters
mongodb_clientMongoDB client
configconfiguration
loggerLogger
outputoutput point cloud
transformerTF transformer for point cloud transformations between coordinate reference frames
originalinput point cloud
outputoutput point cloud

Definition at line 68 of file pcl_db_retrieve_pipeline.h.

◆ ~PointCloudDBRetrievePipeline()

template<typename PointType>
virtual PointCloudDBRetrievePipeline< PointType >::~PointCloudDBRetrievePipeline ( )
inlinevirtual

Destructor.

Definition at line 91 of file pcl_db_retrieve_pipeline.h.

Member Function Documentation

◆ retrieve()

template<typename PointType>
void PointCloudDBRetrievePipeline< PointType >::retrieve ( long long  timestamp,
std::string &  database,
std::string &  collection,
std::string &  target_frame,
long long &  actual_time 
)
inline

Retrieve point clouds.

Parameters
timestamptime for which to retrieve the point cloud
databasedatabase to retrieve from
collectioncollection from which to retrieve the data
target_framecoordinate frame to transform to
actual_timeupon return contains the actual time for which a point cloud was retrieved

Definition at line 107 of file pcl_db_retrieve_pipeline.h.

Referenced by PointCloudDBRetrieveThread::loop().


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