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

#include <fast_correlative_scan_matcher.h>

Public Member Functions

 FastCorrelativeScanMatcher (const ProbabilityGrid &probability_grid, const proto::FastCorrelativeScanMatcherOptions &options)
 
 FastCorrelativeScanMatcher (const FastCorrelativeScanMatcher &)=delete
 
bool Match (const transform::Rigid2d &initial_pose_estimate, const sensor::PointCloud &point_cloud, float min_score, float *score, transform::Rigid2d *pose_estimate) const
 
bool MatchFullSubmap (const sensor::PointCloud &point_cloud, float min_score, float *score, transform::Rigid2d *pose_estimate) const
 
FastCorrelativeScanMatcheroperator= (const FastCorrelativeScanMatcher &)=delete
 
 ~FastCorrelativeScanMatcher ()
 

Private Member Functions

Candidate BranchAndBound (const std::vector< DiscreteScan > &discrete_scans, const SearchParameters &search_parameters, const std::vector< Candidate > &candidates, int candidate_depth, float min_score) const
 
std::vector< CandidateComputeLowestResolutionCandidates (const std::vector< DiscreteScan > &discrete_scans, const SearchParameters &search_parameters) const
 
std::vector< CandidateGenerateLowestResolutionCandidates (const SearchParameters &search_parameters) const
 
bool MatchWithSearchParameters (SearchParameters search_parameters, const transform::Rigid2d &initial_pose_estimate, const sensor::PointCloud &point_cloud, float min_score, float *score, transform::Rigid2d *pose_estimate) const
 
void ScoreCandidates (const PrecomputationGrid &precomputation_grid, const std::vector< DiscreteScan > &discrete_scans, const SearchParameters &search_parameters, std::vector< Candidate > *const candidates) const
 

Private Attributes

MapLimits limits_
 
const proto::FastCorrelativeScanMatcherOptions options_
 
std::unique_ptr< PrecomputationGridStackprecomputation_grid_stack_
 

Detailed Description

Definition at line 98 of file mapping_2d/scan_matching/fast_correlative_scan_matcher.h.

Constructor & Destructor Documentation

cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::FastCorrelativeScanMatcher ( const ProbabilityGrid probability_grid,
const proto::FastCorrelativeScanMatcherOptions &  options 
)
cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::~FastCorrelativeScanMatcher ( )
cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::FastCorrelativeScanMatcher ( const FastCorrelativeScanMatcher )
delete

Member Function Documentation

Candidate cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::BranchAndBound ( const std::vector< DiscreteScan > &  discrete_scans,
const SearchParameters search_parameters,
const std::vector< Candidate > &  candidates,
int  candidate_depth,
float  min_score 
) const
private
std::vector< Candidate > cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::ComputeLowestResolutionCandidates ( const std::vector< DiscreteScan > &  discrete_scans,
const SearchParameters search_parameters 
) const
private
std::vector< Candidate > cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::GenerateLowestResolutionCandidates ( const SearchParameters search_parameters) const
private
bool cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::Match ( const transform::Rigid2d initial_pose_estimate,
const sensor::PointCloud point_cloud,
float  min_score,
float *  score,
transform::Rigid2d pose_estimate 
) const
bool cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::MatchFullSubmap ( const sensor::PointCloud point_cloud,
float  min_score,
float *  score,
transform::Rigid2d pose_estimate 
) const
bool cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::MatchWithSearchParameters ( SearchParameters  search_parameters,
const transform::Rigid2d initial_pose_estimate,
const sensor::PointCloud point_cloud,
float  min_score,
float *  score,
transform::Rigid2d pose_estimate 
) const
private
FastCorrelativeScanMatcher& cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::operator= ( const FastCorrelativeScanMatcher )
delete
void cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::ScoreCandidates ( const PrecomputationGrid precomputation_grid,
const std::vector< DiscreteScan > &  discrete_scans,
const SearchParameters search_parameters,
std::vector< Candidate > *const  candidates 
) const
private

Member Data Documentation

MapLimits cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::limits_
private
const proto::FastCorrelativeScanMatcherOptions cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::options_
private
std::unique_ptr<PrecomputationGridStack> cartographer::mapping_2d::scan_matching::FastCorrelativeScanMatcher::precomputation_grid_stack_
private

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


cartographer
Author(s):
autogenerated on Mon Jun 10 2019 12:51:39