30 #include "ceres/ceres.h" 31 #include "glog/logging.h" 35 namespace scan_matching {
39 proto::CeresScanMatcherOptions2D 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::CeresScanMatcherOptions2D& 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(
76 std::sqrt(static_cast<double>(point_cloud.size())),
78 nullptr , ceres_pose_estimate);
79 CHECK_GT(
options_.translation_weight(), 0.);
80 problem.AddResidualBlock(
82 options_.translation_weight(), target_translation),
83 nullptr , ceres_pose_estimate);
84 CHECK_GT(
options_.rotation_weight(), 0.);
85 problem.AddResidualBlock(
87 options_.rotation_weight(), ceres_pose_estimate[2]),
88 nullptr , ceres_pose_estimate);
93 {ceres_pose_estimate[0], ceres_pose_estimate[1]}, ceres_pose_estimate[2]);
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const sensor::PointCloud &point_cloud, const Grid2D &grid)
const proto::CeresScanMatcherOptions2D options_
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const Eigen::Vector2d &target_translation)
virtual ~CeresScanMatcher2D()
double GetDouble(const std::string &key)
proto::CeresScanMatcherOptions2D CreateCeresScanMatcherOptions2D(common::LuaParameterDictionary *const parameter_dictionary)
proto::ProbabilityGridRangeDataInserterOptions2D options_
CeresScanMatcher2D(const proto::CeresScanMatcherOptions2D &options)
ceres::Solver::Options CreateCeresSolverOptions(const proto::CeresSolverOptions &proto)
std::vector< Eigen::Vector3f > PointCloud
ceres::Solver::Options ceres_solver_options_
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const double target_angle)
std::unique_ptr< LuaParameterDictionary > GetDictionary(const std::string &key)
proto::CeresSolverOptions CreateCeresSolverOptionsProto(common::LuaParameterDictionary *parameter_dictionary)
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