Public Member Functions | Private Member Functions | Private Attributes
cartographer::mapping::scan_matching::FastCorrelativeScanMatcher2D Class Reference

#include <fast_correlative_scan_matcher_2d.h>

List of all members.

Public Member Functions

 FastCorrelativeScanMatcher2D (const Grid2D &grid, const proto::FastCorrelativeScanMatcherOptions2D &options)
 FastCorrelativeScanMatcher2D (const FastCorrelativeScanMatcher2D &)
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
FastCorrelativeScanMatcher2Doperator= (const FastCorrelativeScanMatcher2D &)
 ~FastCorrelativeScanMatcher2D ()

Private Member Functions

Candidate2D BranchAndBound (const std::vector< DiscreteScan2D > &discrete_scans, const SearchParameters &search_parameters, const std::vector< Candidate2D > &candidates, int candidate_depth, float min_score) const
std::vector< Candidate2DComputeLowestResolutionCandidates (const std::vector< DiscreteScan2D > &discrete_scans, const SearchParameters &search_parameters) const
std::vector< Candidate2DGenerateLowestResolutionCandidates (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 PrecomputationGrid2D &precomputation_grid, const std::vector< DiscreteScan2D > &discrete_scans, const SearchParameters &search_parameters, std::vector< Candidate2D > *const candidates) const

Private Attributes

MapLimits limits_
const
proto::FastCorrelativeScanMatcherOptions2D 
options_
std::unique_ptr
< PrecomputationGridStack2D
precomputation_grid_stack_

Detailed Description

Definition at line 112 of file fast_correlative_scan_matcher_2d.h.


Constructor & Destructor Documentation

cartographer::mapping::scan_matching::FastCorrelativeScanMatcher2D::FastCorrelativeScanMatcher2D ( const Grid2D grid,
const proto::FastCorrelativeScanMatcherOptions2D &  options 
)

Definition at line 188 of file fast_correlative_scan_matcher_2d.cc.

Definition at line 196 of file fast_correlative_scan_matcher_2d.cc.


Member Function Documentation

Candidate2D cartographer::mapping::scan_matching::FastCorrelativeScanMatcher2D::BranchAndBound ( const std::vector< DiscreteScan2D > &  discrete_scans,
const SearchParameters search_parameters,
const std::vector< Candidate2D > &  candidates,
int  candidate_depth,
float  min_score 
) const [private]

Definition at line 335 of file fast_correlative_scan_matcher_2d.cc.

std::vector< Candidate2D > cartographer::mapping::scan_matching::FastCorrelativeScanMatcher2D::ComputeLowestResolutionCandidates ( const std::vector< DiscreteScan2D > &  discrete_scans,
const SearchParameters search_parameters 
) const [private]

Definition at line 265 of file fast_correlative_scan_matcher_2d.cc.

Definition at line 277 of file fast_correlative_scan_matcher_2d.cc.

bool cartographer::mapping::scan_matching::FastCorrelativeScanMatcher2D::Match ( const transform::Rigid2d &  initial_pose_estimate,
const sensor::PointCloud &  point_cloud,
float  min_score,
float *  score,
transform::Rigid2d *  pose_estimate 
) const

Definition at line 198 of file fast_correlative_scan_matcher_2d.cc.

bool cartographer::mapping::scan_matching::FastCorrelativeScanMatcher2D::MatchFullSubmap ( const sensor::PointCloud &  point_cloud,
float  min_score,
float *  score,
transform::Rigid2d *  pose_estimate 
) const

Definition at line 210 of file fast_correlative_scan_matcher_2d.cc.

bool cartographer::mapping::scan_matching::FastCorrelativeScanMatcher2D::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]

Definition at line 227 of file fast_correlative_scan_matcher_2d.cc.

FastCorrelativeScanMatcher2D& cartographer::mapping::scan_matching::FastCorrelativeScanMatcher2D::operator= ( const FastCorrelativeScanMatcher2D )
void cartographer::mapping::scan_matching::FastCorrelativeScanMatcher2D::ScoreCandidates ( const PrecomputationGrid2D precomputation_grid,
const std::vector< DiscreteScan2D > &  discrete_scans,
const SearchParameters search_parameters,
std::vector< Candidate2D > *const  candidates 
) const [private]

Definition at line 314 of file fast_correlative_scan_matcher_2d.cc.


Member Data Documentation

Definition at line 162 of file fast_correlative_scan_matcher_2d.h.

const proto::FastCorrelativeScanMatcherOptions2D cartographer::mapping::scan_matching::FastCorrelativeScanMatcher2D::options_ [private]

Definition at line 161 of file fast_correlative_scan_matcher_2d.h.

Definition at line 163 of file fast_correlative_scan_matcher_2d.h.


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


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:36