Classes | Typedefs | Functions | Variables
cartographer::mapping::scan_matching Namespace Reference

Classes

struct  Candidate2D
struct  Candidate3D
class  CeresScanMatcher2D
class  CeresScanMatcher3D
struct  DiscreteScan3D
class  FastCorrelativeScanMatcher2D
class  FastCorrelativeScanMatcher3D
class  InterpolatedGrid
class  InterpolatedTSDF2D
class  OccupiedSpaceCostFunction3D
class  PrecomputationGrid2D
class  PrecomputationGrid3D
class  PrecomputationGridStack2D
class  PrecomputationGridStack3D
class  RealTimeCorrelativeScanMatcher2D
class  RealTimeCorrelativeScanMatcher3D
class  RotationalScanMatcher
class  RotationDeltaCostFunctor2D
class  RotationDeltaCostFunctor3D
struct  SearchParameters
class  TranslationDeltaCostFunctor2D
class  TranslationDeltaCostFunctor3D
class  TSDFMatchCostFunction2D

Typedefs

typedef std::vector
< Eigen::Array2i > 
DiscreteScan2D

Functions

PrecomputationGrid3D ConvertToPrecomputationGrid (const HybridGrid &hybrid_grid)
proto::CeresScanMatcherOptions2D CreateCeresScanMatcherOptions2D (common::LuaParameterDictionary *const parameter_dictionary)
proto::CeresScanMatcherOptions3D CreateCeresScanMatcherOptions3D (common::LuaParameterDictionary *const parameter_dictionary)
proto::FastCorrelativeScanMatcherOptions2D CreateFastCorrelativeScanMatcherOptions2D (common::LuaParameterDictionary *const parameter_dictionary)
proto::FastCorrelativeScanMatcherOptions3D CreateFastCorrelativeScanMatcherOptions3D (common::LuaParameterDictionary *const parameter_dictionary)
ceres::CostFunction * CreateOccupiedSpaceCostFunction2D (const double scaling_factor, const sensor::PointCloud &point_cloud, const Grid2D &grid)
proto::RealTimeCorrelativeScanMatcherOptions CreateRealTimeCorrelativeScanMatcherOptions (common::LuaParameterDictionary *const parameter_dictionary)
ceres::CostFunction * CreateTSDFMatchCostFunction2D (const double scaling_factor, const sensor::PointCloud &point_cloud, const TSDF2D &tsdf)
std::vector< DiscreteScan2DDiscretizeScans (const MapLimits &map_limits, const std::vector< sensor::PointCloud > &scans, const Eigen::Translation2f &initial_translation)
std::vector< sensor::PointCloud > GenerateRotatedScans (const sensor::PointCloud &point_cloud, const SearchParameters &search_parameters)
PrecomputationGrid3D PrecomputeGrid (const PrecomputationGrid3D &grid, const bool half_resolution, const Eigen::Array3i &shift)

Variables

std::function< float(const
transform::Rigid3f &)> 
CreateLowResolutionMatcher (const HybridGrid *low_resolution_grid, const sensor::PointCloud *points)

Typedef Documentation

typedef std::vector<Eigen::Array2i> cartographer::mapping::scan_matching::DiscreteScan2D

Definition at line 32 of file correlative_scan_matcher_2d.h.


Function Documentation

Definition at line 49 of file precomputation_grid_3d.cc.

proto::CeresScanMatcherOptions2D cartographer::mapping::scan_matching::CreateCeresScanMatcherOptions2D ( common::LuaParameterDictionary *const  parameter_dictionary)

Definition at line 38 of file ceres_scan_matcher_2d.cc.

proto::CeresScanMatcherOptions3D cartographer::mapping::scan_matching::CreateCeresScanMatcherOptions3D ( common::LuaParameterDictionary *const  parameter_dictionary)

Definition at line 39 of file ceres_scan_matcher_3d.cc.

proto::FastCorrelativeScanMatcherOptions2D cartographer::mapping::scan_matching::CreateFastCorrelativeScanMatcherOptions2D ( common::LuaParameterDictionary *const  parameter_dictionary)

Definition at line 79 of file fast_correlative_scan_matcher_2d.cc.

proto::FastCorrelativeScanMatcherOptions3D cartographer::mapping::scan_matching::CreateFastCorrelativeScanMatcherOptions3D ( common::LuaParameterDictionary *const  parameter_dictionary)

Definition at line 37 of file fast_correlative_scan_matcher_3d.cc.

ceres::CostFunction * cartographer::mapping::scan_matching::CreateOccupiedSpaceCostFunction2D ( const double  scaling_factor,
const sensor::PointCloud &  point_cloud,
const Grid2D &  grid 
)

Definition at line 109 of file occupied_space_cost_function_2d.cc.

proto::RealTimeCorrelativeScanMatcherOptions cartographer::mapping::scan_matching::CreateRealTimeCorrelativeScanMatcherOptions ( common::LuaParameterDictionary *const  parameter_dictionary)

Definition at line 8 of file real_time_correlative_scan_matcher.cc.

ceres::CostFunction * cartographer::mapping::scan_matching::CreateTSDFMatchCostFunction2D ( const double  scaling_factor,
const sensor::PointCloud &  point_cloud,
const TSDF2D &  tsdf 
)

Definition at line 77 of file tsdf_match_cost_function_2d.cc.

std::vector< DiscreteScan2D > cartographer::mapping::scan_matching::DiscretizeScans ( const MapLimits &  map_limits,
const std::vector< sensor::PointCloud > &  scans,
const Eigen::Translation2f &  initial_translation 
)

Definition at line 111 of file correlative_scan_matcher_2d.cc.

std::vector< sensor::PointCloud > cartographer::mapping::scan_matching::GenerateRotatedScans ( const sensor::PointCloud &  point_cloud,
const SearchParameters &  search_parameters 
)

Definition at line 93 of file correlative_scan_matcher_2d.cc.

PrecomputationGrid3D cartographer::mapping::scan_matching::PrecomputeGrid ( const PrecomputationGrid3D &  grid,
const bool  half_resolution,
const Eigen::Array3i &  shift 
)

Definition at line 63 of file precomputation_grid_3d.cc.


Variable Documentation

std::function< float(const transform::Rigid3f &)> cartographer::mapping::scan_matching::CreateLowResolutionMatcher

Definition at line 23 of file low_resolution_matcher.cc.



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