17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_CERES_SCAN_MATCHER_2D_H_ 18 #define CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_CERES_SCAN_MATCHER_2D_H_ 26 #include "cartographer/mapping/proto/scan_matching/ceres_scan_matcher_options_2d.pb.h" 28 #include "ceres/ceres.h" 32 namespace scan_matching {
35 common::LuaParameterDictionary* parameter_dictionary);
49 void Match(
const Eigen::Vector2d& target_translation,
53 ceres::Solver::Summary* summary)
const;
56 const proto::CeresScanMatcherOptions2D
options_;
64 #endif // CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_CERES_SCAN_MATCHER_2D_H_
const proto::CeresScanMatcherOptions2D options_
virtual ~CeresScanMatcher2D()
proto::CeresScanMatcherOptions2D CreateCeresScanMatcherOptions2D(common::LuaParameterDictionary *const parameter_dictionary)
CeresScanMatcher2D(const proto::CeresScanMatcherOptions2D &options)
std::vector< Eigen::Vector3f > PointCloud
ceres::Solver::Options ceres_solver_options_
void Match(const Eigen::Vector2d &target_translation, const transform::Rigid2d &initial_pose_estimate, const sensor::PointCloud &point_cloud, const Grid2D &grid, transform::Rigid2d *pose_estimate, ceres::Solver::Summary *summary) const
CeresScanMatcher2D & operator=(const CeresScanMatcher2D &)=delete