MapRegistration Class Reference

#include <armarx/localization_and_mapping/cartographer_adapter/map_registration/MapRegistration.h>

Classes

struct  Association
 
struct  Cluster
 
struct  LocalPointCloud
 
struct  ModelCorrection
 

Public Types

using Associations = std::vector< Association >
 
using Clusters = std::vector< Cluster >
 
using Point = pcl::PointXYZ
 
using PointCloud = pcl::PointCloud< Point >
 

Public Member Functions

ModelCorrection alignModelToCluster (const wykobi::Model &model, const Cluster &cluster, const Eigen::Isometry3f &world_T_map) const
 
void computeBoundingBox (const PointCloud::ConstPtr &cloud)
 
ModelCorrection computeCombinedCorrection (const std::vector< wykobi::Model > &models, const std::vector< ModelCorrection > &modelCorrections) const
 
MapRegistration::ModelCorrection computeCorrection (const MapRegistration::Associations &associations)
 
Clusters detectClusters (const PointCloud::ConstPtr &cloud) const
 
const RotatedRectgetBoundingBox () const
 
 MapRegistration (std::unique_ptr<::cartographer::mapping::MapBuilderInterface > mapBuilder)
 
TimeRange mapTimeRange () const
 
Associations matchModelsToClusters (const std::vector< wykobi::Model > &models, const Clusters &clusters, const Eigen::Isometry3f &world_T_map) const
 
simox::math::InterpolatingTimeQueue< simox::math::PoseStamped > robotPoseQueue () const
 
std::vector< Eigen::Isometry3f > robotPoses () const
 
void visualizeResult (const PointCloud::ConstPtr &cloud, const std::vector< wykobi::Model > &models, const ModelCorrection &combinedCorrection) const
 
 ~MapRegistration ()
 

Detailed Description

Definition at line 102 of file MapRegistration.h.

Member Typedef Documentation

◆ Associations

using Associations = std::vector<Association>

Definition at line 139 of file MapRegistration.h.

◆ Clusters

using Clusters = std::vector<Cluster>

Definition at line 121 of file MapRegistration.h.

◆ Point

using Point = pcl::PointXYZ

Definition at line 109 of file MapRegistration.h.

◆ PointCloud

using PointCloud = pcl::PointCloud<Point>

Definition at line 110 of file MapRegistration.h.

Constructor & Destructor Documentation

◆ MapRegistration()

MapRegistration ( std::unique_ptr<::cartographer::mapping::MapBuilderInterface >  mapBuilder)

Definition at line 107 of file MapRegistration.cpp.

◆ ~MapRegistration()

~MapRegistration ( )
default

Member Function Documentation

◆ alignModelToCluster()

MapRegistration::ModelCorrection alignModelToCluster ( const wykobi::Model model,
const Cluster cluster,
const Eigen::Isometry3f &  world_T_map 
) const

Definition at line 229 of file MapRegistration.cpp.

◆ computeBoundingBox()

void computeBoundingBox ( const PointCloud::ConstPtr &  cloud)

Definition at line 406 of file MapRegistration.cpp.

+ Here is the call graph for this function:

◆ computeCombinedCorrection()

MapRegistration::ModelCorrection computeCombinedCorrection ( const std::vector< wykobi::Model > &  models,
const std::vector< ModelCorrection > &  modelCorrections 
) const

Definition at line 273 of file MapRegistration.cpp.

+ Here is the call graph for this function:

◆ computeCorrection()

MapRegistration::ModelCorrection computeCorrection ( const MapRegistration::Associations associations)

Definition at line 249 of file MapRegistration.cpp.

+ Here is the call graph for this function:

◆ detectClusters()

MapRegistration::Clusters detectClusters ( const PointCloud::ConstPtr &  cloud) const

Definition at line 134 of file MapRegistration.cpp.

+ Here is the call graph for this function:

◆ getBoundingBox()

const RotatedRect& getBoundingBox ( ) const
inline

Definition at line 180 of file MapRegistration.h.

◆ mapTimeRange()

TimeRange mapTimeRange ( ) const

Definition at line 369 of file MapRegistration.cpp.

◆ matchModelsToClusters()

MapRegistration::Associations matchModelsToClusters ( const std::vector< wykobi::Model > &  models,
const Clusters clusters,
const Eigen::Isometry3f &  world_T_map 
) const

Definition at line 212 of file MapRegistration.cpp.

+ Here is the call graph for this function:

◆ robotPoseQueue()

simox::math::InterpolatingTimeQueue< simox::math::PoseStamped > robotPoseQueue ( ) const

Definition at line 117 of file MapRegistration.cpp.

+ Here is the caller graph for this function:

◆ robotPoses()

std::vector< Eigen::Isometry3f > robotPoses ( ) const

Definition at line 378 of file MapRegistration.cpp.

+ Here is the call graph for this function:

◆ visualizeResult()

void visualizeResult ( const PointCloud::ConstPtr &  cloud,
const std::vector< wykobi::Model > &  models,
const ModelCorrection combinedCorrection 
) const

Definition at line 340 of file MapRegistration.cpp.


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