30 #include "ceres/ceres.h" 31 #include "glog/logging.h" 34 namespace mapping_2d {
35 namespace scan_matching {
39 proto::CeresScanMatcherOptions options;
40 options.set_occupied_space_weight(
41 parameter_dictionary->
GetDouble(
"occupied_space_weight"));
42 options.set_translation_weight(
43 parameter_dictionary->
GetDouble(
"translation_weight"));
44 options.set_rotation_weight(
45 parameter_dictionary->
GetDouble(
"rotation_weight"));
46 *options.mutable_ceres_solver_options() =
48 parameter_dictionary->
GetDictionary(
"ceres_solver_options").get());
53 const proto::CeresScanMatcherOptions& options)
55 ceres_solver_options_(
67 ceres::Solver::Summary*
const summary)
const {
68 double ceres_pose_estimate[3] = {initial_pose_estimate.
translation().x(),
70 initial_pose_estimate.
rotation().angle()};
71 ceres::Problem problem;
72 CHECK_GT(
options_.occupied_space_weight(), 0.);
73 problem.AddResidualBlock(
78 std::sqrt(static_cast<double>(point_cloud.size())),
79 point_cloud, probability_grid),
81 nullptr, ceres_pose_estimate);
82 CHECK_GT(
options_.translation_weight(), 0.);
83 problem.AddResidualBlock(
84 new ceres::AutoDiffCostFunction<TranslationDeltaCostFunctor, 2, 3>(
87 nullptr, ceres_pose_estimate);
88 CHECK_GT(
options_.rotation_weight(), 0.);
89 problem.AddResidualBlock(
90 new ceres::AutoDiffCostFunction<RotationDeltaCostFunctor, 1, 3>(
92 ceres_pose_estimate[2])),
93 nullptr, ceres_pose_estimate);
98 {ceres_pose_estimate[0], ceres_pose_estimate[1]}, ceres_pose_estimate[2]);
proto::RangeDataInserterOptions options_
const proto::CeresScanMatcherOptions options_
CeresScanMatcher(const proto::CeresScanMatcherOptions &options)
double GetDouble(const string &key)
proto::CeresScanMatcherOptions CreateCeresScanMatcherOptions(common::LuaParameterDictionary *const parameter_dictionary)
ceres::Solver::Options CreateCeresSolverOptions(const proto::CeresSolverOptions &proto)
std::vector< Eigen::Vector3f > PointCloud
void Match(const transform::Rigid2d &previous_pose, const transform::Rigid2d &initial_pose_estimate, const sensor::PointCloud &point_cloud, const ProbabilityGrid &probability_grid, transform::Rigid2d *pose_estimate, ceres::Solver::Summary *summary) const
ceres::Solver::Options ceres_solver_options_
proto::CeresSolverOptions CreateCeresSolverOptionsProto(common::LuaParameterDictionary *parameter_dictionary)
virtual ~CeresScanMatcher()
std::unique_ptr< LuaParameterDictionary > GetDictionary(const string &key)