Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/mapping/internal/3d/scan_matching/ceres_scan_matcher_3d.h"
00018
00019 #include <string>
00020 #include <utility>
00021 #include <vector>
00022
00023 #include "absl/memory/memory.h"
00024 #include "cartographer/common/ceres_solver_options.h"
00025 #include "cartographer/mapping/internal/3d/rotation_parameterization.h"
00026 #include "cartographer/mapping/internal/3d/scan_matching/occupied_space_cost_function_3d.h"
00027 #include "cartographer/mapping/internal/3d/scan_matching/rotation_delta_cost_functor_3d.h"
00028 #include "cartographer/mapping/internal/3d/scan_matching/translation_delta_cost_functor_3d.h"
00029 #include "cartographer/mapping/internal/optimization/ceres_pose.h"
00030 #include "cartographer/transform/rigid_transform.h"
00031 #include "cartographer/transform/transform.h"
00032 #include "ceres/ceres.h"
00033 #include "glog/logging.h"
00034
00035 namespace cartographer {
00036 namespace mapping {
00037 namespace scan_matching {
00038
00039 proto::CeresScanMatcherOptions3D CreateCeresScanMatcherOptions3D(
00040 common::LuaParameterDictionary* const parameter_dictionary) {
00041 proto::CeresScanMatcherOptions3D options;
00042 for (int i = 0;; ++i) {
00043 const std::string lua_identifier =
00044 "occupied_space_weight_" + std::to_string(i);
00045 if (!parameter_dictionary->HasKey(lua_identifier)) {
00046 break;
00047 }
00048 options.add_occupied_space_weight(
00049 parameter_dictionary->GetDouble(lua_identifier));
00050 }
00051 options.set_translation_weight(
00052 parameter_dictionary->GetDouble("translation_weight"));
00053 options.set_rotation_weight(
00054 parameter_dictionary->GetDouble("rotation_weight"));
00055 options.set_only_optimize_yaw(
00056 parameter_dictionary->GetBool("only_optimize_yaw"));
00057 *options.mutable_ceres_solver_options() =
00058 common::CreateCeresSolverOptionsProto(
00059 parameter_dictionary->GetDictionary("ceres_solver_options").get());
00060 return options;
00061 }
00062
00063 CeresScanMatcher3D::CeresScanMatcher3D(
00064 const proto::CeresScanMatcherOptions3D& options)
00065 : options_(options),
00066 ceres_solver_options_(
00067 common::CreateCeresSolverOptions(options.ceres_solver_options())) {
00068 ceres_solver_options_.linear_solver_type = ceres::DENSE_QR;
00069 }
00070
00071 void CeresScanMatcher3D::Match(
00072 const Eigen::Vector3d& target_translation,
00073 const transform::Rigid3d& initial_pose_estimate,
00074 const std::vector<PointCloudAndHybridGridPointers>&
00075 point_clouds_and_hybrid_grids,
00076 transform::Rigid3d* const pose_estimate,
00077 ceres::Solver::Summary* const summary) {
00078 ceres::Problem problem;
00079 optimization::CeresPose ceres_pose(
00080 initial_pose_estimate, nullptr ,
00081 options_.only_optimize_yaw()
00082 ? std::unique_ptr<ceres::LocalParameterization>(
00083 absl::make_unique<ceres::AutoDiffLocalParameterization<
00084 YawOnlyQuaternionPlus, 4, 1>>())
00085 : std::unique_ptr<ceres::LocalParameterization>(
00086 absl::make_unique<ceres::QuaternionParameterization>()),
00087 &problem);
00088
00089 CHECK_EQ(options_.occupied_space_weight_size(),
00090 point_clouds_and_hybrid_grids.size());
00091 for (size_t i = 0; i != point_clouds_and_hybrid_grids.size(); ++i) {
00092 CHECK_GT(options_.occupied_space_weight(i), 0.);
00093 const sensor::PointCloud& point_cloud =
00094 *point_clouds_and_hybrid_grids[i].first;
00095 const HybridGrid& hybrid_grid = *point_clouds_and_hybrid_grids[i].second;
00096 problem.AddResidualBlock(
00097 OccupiedSpaceCostFunction3D::CreateAutoDiffCostFunction(
00098 options_.occupied_space_weight(i) /
00099 std::sqrt(static_cast<double>(point_cloud.size())),
00100 point_cloud, hybrid_grid),
00101 nullptr , ceres_pose.translation(),
00102 ceres_pose.rotation());
00103 }
00104 CHECK_GT(options_.translation_weight(), 0.);
00105 problem.AddResidualBlock(
00106 TranslationDeltaCostFunctor3D::CreateAutoDiffCostFunction(
00107 options_.translation_weight(), target_translation),
00108 nullptr , ceres_pose.translation());
00109 CHECK_GT(options_.rotation_weight(), 0.);
00110 problem.AddResidualBlock(
00111 RotationDeltaCostFunctor3D::CreateAutoDiffCostFunction(
00112 options_.rotation_weight(), initial_pose_estimate.rotation()),
00113 nullptr , ceres_pose.rotation());
00114
00115 ceres::Solve(ceres_solver_options_, &problem, summary);
00116
00117 *pose_estimate = ceres_pose.ToRigid();
00118 }
00119
00120 }
00121 }
00122 }