31 #include "ceres/ceres.h" 32 #include "glog/logging.h" 35 namespace mapping_3d {
36 namespace scan_matching {
39 struct YawOnlyQuaternionPlus {
41 bool operator()(
const T* x,
const T* delta, T* x_plus_delta)
const {
42 const T clamped_delta =
common::Clamp(delta[0], T(-0.5), T(0.5));
44 q_delta[0] = ceres::sqrt(1. - clamped_delta * clamped_delta);
47 q_delta[3] = clamped_delta;
48 ceres::QuaternionProduct(q_delta, x, x_plus_delta);
57 proto::CeresScanMatcherOptions options;
58 for (
int i = 0;; ++i) {
59 const string lua_identifier =
"occupied_space_weight_" + std::to_string(i);
60 if (!parameter_dictionary->
HasKey(lua_identifier)) {
63 options.add_occupied_space_weight(
64 parameter_dictionary->
GetDouble(lua_identifier));
66 options.set_translation_weight(
67 parameter_dictionary->
GetDouble(
"translation_weight"));
68 options.set_rotation_weight(
69 parameter_dictionary->
GetDouble(
"rotation_weight"));
70 options.set_only_optimize_yaw(
71 parameter_dictionary->
GetBool(
"only_optimize_yaw"));
72 *options.mutable_ceres_solver_options() =
74 parameter_dictionary->
GetDictionary(
"ceres_solver_options").get());
79 const proto::CeresScanMatcherOptions& options)
81 ceres_solver_options_(
88 const std::vector<PointCloudAndHybridGridPointers>&
89 point_clouds_and_hybrid_grids,
91 ceres::Solver::Summary*
const summary) {
92 ceres::Problem problem;
94 initial_pose_estimate,
nullptr ,
96 ? std::unique_ptr<ceres::LocalParameterization>(
98 YawOnlyQuaternionPlus, 4, 1>>())
99 : std::unique_ptr<ceres::LocalParameterization>(
100 common::make_unique<ceres::QuaternionParameterization>()),
103 CHECK_EQ(
options_.occupied_space_weight_size(),
104 point_clouds_and_hybrid_grids.size());
105 for (
size_t i = 0; i != point_clouds_and_hybrid_grids.size(); ++i) {
106 CHECK_GT(
options_.occupied_space_weight(i), 0.);
108 *point_clouds_and_hybrid_grids[i].first;
109 const HybridGrid& hybrid_grid = *point_clouds_and_hybrid_grids[i].second;
110 problem.AddResidualBlock(
112 ceres::DYNAMIC, 3, 4>(
115 std::sqrt(static_cast<double>(point_cloud.size())),
116 point_cloud, hybrid_grid),
118 nullptr, ceres_pose.translation(), ceres_pose.rotation());
120 CHECK_GT(
options_.translation_weight(), 0.);
121 problem.AddResidualBlock(
122 new ceres::AutoDiffCostFunction<TranslationDeltaCostFunctor, 3, 3>(
125 nullptr, ceres_pose.translation());
126 CHECK_GT(
options_.rotation_weight(), 0.);
127 problem.AddResidualBlock(
128 new ceres::AutoDiffCostFunction<RotationDeltaCostFunctor, 3, 4>(
131 nullptr, ceres_pose.rotation());
135 *pose_estimate = ceres_pose.ToRigid();
proto::RangeDataInserterOptions options_
bool GetBool(const string &key)
double GetDouble(const string &key)
void Match(const transform::Rigid3d &previous_pose, const transform::Rigid3d &initial_pose_estimate, const std::vector< PointCloudAndHybridGridPointers > &point_clouds_and_hybrid_grids, transform::Rigid3d *pose_estimate, ceres::Solver::Summary *summary)
ceres::Solver::Options ceres_solver_options_
proto::CeresScanMatcherOptions CreateCeresScanMatcherOptions(common::LuaParameterDictionary *const parameter_dictionary)
CeresScanMatcher(const proto::CeresScanMatcherOptions &options)
ceres::Solver::Options CreateCeresSolverOptions(const proto::CeresSolverOptions &proto)
std::vector< Eigen::Vector3f > PointCloud
bool HasKey(const string &key) const
proto::CeresSolverOptions CreateCeresSolverOptionsProto(common::LuaParameterDictionary *parameter_dictionary)
T Clamp(const T value, const T min, const T max)
std::unique_ptr< LuaParameterDictionary > GetDictionary(const string &key)
_Unique_if< T >::_Single_object make_unique(Args &&...args)
const proto::CeresScanMatcherOptions options_