32 #include "ceres/ceres.h" 33 #include "glog/logging.h" 36 namespace mapping_2d {
37 namespace sparse_pose_graph {
45 return {{pose.translation().x(), pose.translation().y(),
46 pose.normalized_angle()}};
57 const mapping::sparse_pose_graph::proto::OptimizationProblemOptions&
65 const Eigen::Vector3d& linear_acceleration,
66 const Eigen::Vector3d& angular_velocity) {
67 CHECK_GE(trajectory_id, 0);
69 std::max(
imu_data_.size(),
static_cast<size_t>(trajectory_id) + 1));
78 CHECK_GE(trajectory_id, 0);
80 std::max(
node_data_.size(),
static_cast<size_t>(trajectory_id) + 1));
82 NodeData{
time, initial_point_cloud_pose, point_cloud_pose});
87 CHECK_GE(trajectory_id, 0);
89 std::max(
submap_data_.size(),
static_cast<size_t>(trajectory_id) + 1));
94 options_.mutable_ceres_solver_options()->set_max_num_iterations(
104 ceres::Problem::Options problem_options;
105 ceres::Problem problem(problem_options);
109 std::vector<std::deque<std::array<double, 3>>> C_submaps(
submap_data_.size());
110 std::vector<std::deque<std::array<double, 3>>> C_nodes(
node_data_.size());
111 for (
size_t trajectory_id = 0; trajectory_id !=
submap_data_.size();
113 for (
size_t submap_index = 0;
114 submap_index !=
submap_data_[trajectory_id].size(); ++submap_index) {
115 if (trajectory_id == 0 && submap_index == 0) {
117 C_submaps[trajectory_id].push_back(
119 problem.AddParameterBlock(C_submaps[trajectory_id].back().data(), 3);
120 problem.SetParameterBlockConstant(
121 C_submaps[trajectory_id].back().data());
123 C_submaps[trajectory_id].push_back(
124 FromPose(
submap_data_[trajectory_id][submap_index].pose));
125 problem.AddParameterBlock(C_submaps[trajectory_id].back().data(), 3);
129 for (
size_t trajectory_id = 0; trajectory_id !=
node_data_.size();
131 C_nodes[trajectory_id].resize(
node_data_[trajectory_id].size());
132 for (
size_t node_index = 0; node_index !=
node_data_[trajectory_id].size();
134 C_nodes[trajectory_id][node_index] =
135 FromPose(
node_data_[trajectory_id][node_index].point_cloud_pose);
136 problem.AddParameterBlock(C_nodes[trajectory_id][node_index].data(), 3);
141 for (
const Constraint& constraint : constraints) {
142 problem.AddResidualBlock(
143 new ceres::AutoDiffCostFunction<SpaCostFunction, 3, 3, 3>(
147 ?
new ceres::HuberLoss(
options_.huber_scale())
149 C_submaps.at(constraint.submap_id.trajectory_id)
150 .at(constraint.submap_id.submap_index)
152 C_nodes.at(constraint.node_id.trajectory_id)
153 .at(constraint.node_id.node_index)
158 for (
size_t trajectory_id = 0; trajectory_id !=
node_data_.size();
160 for (
size_t node_index = 1; node_index <
node_data_[trajectory_id].size();
162 problem.AddResidualBlock(
163 new ceres::AutoDiffCostFunction<SpaCostFunction, 3, 3, 3>(
166 .initial_point_cloud_pose.inverse() *
168 .initial_point_cloud_pose),
169 options_.consecutive_scan_translation_penalty_factor(),
170 options_.consecutive_scan_rotation_penalty_factor()})),
172 C_nodes[trajectory_id][node_index - 1].data(),
173 C_nodes[trajectory_id][node_index].data());
178 ceres::Solver::Summary summary;
183 if (
options_.log_solver_summary()) {
184 LOG(INFO) << summary.FullReport();
188 for (
size_t trajectory_id = 0; trajectory_id !=
submap_data_.size();
190 for (
size_t submap_index = 0;
191 submap_index !=
submap_data_[trajectory_id].size(); ++submap_index) {
193 ToPose(C_submaps[trajectory_id][submap_index]);
196 for (
size_t trajectory_id = 0; trajectory_id !=
node_data_.size();
198 for (
size_t node_index = 0; node_index !=
node_data_[trajectory_id].size();
200 node_data_[trajectory_id][node_index].point_cloud_pose =
201 ToPose(C_nodes[trajectory_id][node_index]);
void AddSubmap(int trajectory_id, const transform::Rigid2d &submap_pose)
proto::RangeDataInserterOptions options_
void SetMaxNumIterations(int32 max_num_iterations)
OptimizationProblem(const mapping::sparse_pose_graph::proto::OptimizationProblemOptions &options)
void Solve(const std::vector< Constraint > &constraints)
mapping::sparse_pose_graph::proto::OptimizationProblemOptions options_
UniversalTimeScaleClock::time_point Time
void AddImuData(int trajectory_id, common::Time time, const Eigen::Vector3d &linear_acceleration, const Eigen::Vector3d &angular_velocity)
const std::vector< std::vector< SubmapData > > & submap_data() const
std::vector< std::vector< NodeData > > node_data_
const std::vector< std::vector< NodeData > > & node_data() const
std::vector< std::deque< mapping_3d::ImuData > > imu_data_
std::vector< std::vector< SubmapData > > submap_data_
ceres::Solver::Options CreateCeresSolverOptions(const proto::CeresSolverOptions &proto)
void AddTrajectoryNode(int trajectory_id, common::Time time, const transform::Rigid2d &initial_point_cloud_pose, const transform::Rigid2d &point_cloud_pose)