Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher Class Reference

#include <fast_correlative_scan_matcher.h>

Classes

struct  SearchParameters
 

Public Member Functions

 FastCorrelativeScanMatcher (const HybridGrid &hybrid_grid, const std::vector< mapping::TrajectoryNode > &nodes, const proto::FastCorrelativeScanMatcherOptions &options)
 
 FastCorrelativeScanMatcher (const FastCorrelativeScanMatcher &)=delete
 
bool Match (const transform::Rigid3d &initial_pose_estimate, const sensor::PointCloud &coarse_point_cloud, const sensor::PointCloud &fine_point_cloud, float min_score, float *score, transform::Rigid3d *pose_estimate) const
 
bool MatchFullSubmap (const Eigen::Quaterniond &gravity_alignment, const sensor::PointCloud &coarse_point_cloud, const sensor::PointCloud &fine_point_cloud, float min_score, float *score, transform::Rigid3d *pose_estimate) const
 
FastCorrelativeScanMatcheroperator= (const FastCorrelativeScanMatcher &)=delete
 
 ~FastCorrelativeScanMatcher ()
 

Private Member Functions

Candidate BranchAndBound (const SearchParameters &search_parameters, const std::vector< DiscreteScan > &discrete_scans, const std::vector< Candidate > &candidates, int candidate_depth, float min_score) const
 
std::vector< CandidateComputeLowestResolutionCandidates (const SearchParameters &search_parameters, const std::vector< DiscreteScan > &discrete_scans) const
 
DiscreteScan DiscretizeScan (const SearchParameters &search_parameters, const sensor::PointCloud &point_cloud, const transform::Rigid3f &pose) const
 
std::vector< DiscreteScanGenerateDiscreteScans (const SearchParameters &search_parameters, const sensor::PointCloud &coarse_point_cloud, const sensor::PointCloud &fine_point_cloud, const transform::Rigid3f &initial_pose) const
 
std::vector< CandidateGenerateLowestResolutionCandidates (const SearchParameters &search_parameters, int num_discrete_scans) const
 
bool MatchWithSearchParameters (const SearchParameters &search_parameters, const transform::Rigid3d &initial_pose_estimate, const sensor::PointCloud &coarse_point_cloud, const sensor::PointCloud &fine_point_cloud, float min_score, float *score, transform::Rigid3d *pose_estimate) const
 
void ScoreCandidates (int depth, const std::vector< DiscreteScan > &discrete_scans, std::vector< Candidate > *const candidates) const
 

Private Attributes

const proto::FastCorrelativeScanMatcherOptions options_
 
std::unique_ptr< PrecomputationGridStackprecomputation_grid_stack_
 
const float resolution_
 
RotationalScanMatcher rotational_scan_matcher_
 
const int width_in_voxels_
 

Detailed Description

Definition at line 70 of file mapping_3d/scan_matching/fast_correlative_scan_matcher.h.

Constructor & Destructor Documentation

cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::FastCorrelativeScanMatcher ( const HybridGrid hybrid_grid,
const std::vector< mapping::TrajectoryNode > &  nodes,
const proto::FastCorrelativeScanMatcherOptions &  options 
)
cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::~FastCorrelativeScanMatcher ( )
cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::FastCorrelativeScanMatcher ( const FastCorrelativeScanMatcher )
delete

Member Function Documentation

Candidate cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::BranchAndBound ( const SearchParameters search_parameters,
const std::vector< DiscreteScan > &  discrete_scans,
const std::vector< Candidate > &  candidates,
int  candidate_depth,
float  min_score 
) const
private
std::vector< Candidate > cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::ComputeLowestResolutionCandidates ( const SearchParameters search_parameters,
const std::vector< DiscreteScan > &  discrete_scans 
) const
private
DiscreteScan cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::DiscretizeScan ( const SearchParameters search_parameters,
const sensor::PointCloud point_cloud,
const transform::Rigid3f pose 
) const
private
std::vector< DiscreteScan > cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::GenerateDiscreteScans ( const SearchParameters search_parameters,
const sensor::PointCloud coarse_point_cloud,
const sensor::PointCloud fine_point_cloud,
const transform::Rigid3f initial_pose 
) const
private
std::vector< Candidate > cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::GenerateLowestResolutionCandidates ( const SearchParameters search_parameters,
int  num_discrete_scans 
) const
private
bool cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::Match ( const transform::Rigid3d initial_pose_estimate,
const sensor::PointCloud coarse_point_cloud,
const sensor::PointCloud fine_point_cloud,
float  min_score,
float *  score,
transform::Rigid3d pose_estimate 
) const
bool cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::MatchFullSubmap ( const Eigen::Quaterniond &  gravity_alignment,
const sensor::PointCloud coarse_point_cloud,
const sensor::PointCloud fine_point_cloud,
float  min_score,
float *  score,
transform::Rigid3d pose_estimate 
) const
bool cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::MatchWithSearchParameters ( const SearchParameters search_parameters,
const transform::Rigid3d initial_pose_estimate,
const sensor::PointCloud coarse_point_cloud,
const sensor::PointCloud fine_point_cloud,
float  min_score,
float *  score,
transform::Rigid3d pose_estimate 
) const
private
FastCorrelativeScanMatcher& cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::operator= ( const FastCorrelativeScanMatcher )
delete
void cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::ScoreCandidates ( int  depth,
const std::vector< DiscreteScan > &  discrete_scans,
std::vector< Candidate > *const  candidates 
) const
private

Member Data Documentation

const proto::FastCorrelativeScanMatcherOptions cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::options_
private
std::unique_ptr<PrecomputationGridStack> cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::precomputation_grid_stack_
private
const float cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::resolution_
private
RotationalScanMatcher cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::rotational_scan_matcher_
private
const int cartographer::mapping_3d::scan_matching::FastCorrelativeScanMatcher::width_in_voxels_
private

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


cartographer
Author(s):
autogenerated on Wed Jun 5 2019 21:58:01