35 #include "ceres/ceres.h" 36 #include "glog/logging.h" 40 namespace optimization {
43 using ::cartographer::mapping::optimization::CeresPose;
50 return {{pose.
translation().x(), pose.translation().y(),
51 pose.normalized_angle()}};
62 const LandmarkNode::LandmarkObservation& observation,
63 const NodeSpec2D& prev_node,
const NodeSpec2D& next_node,
64 const std::array<double, 3>& prev_node_pose,
65 const std::array<double, 3>& next_node_pose) {
66 const double interpolation_parameter =
70 const std::tuple<std::array<double, 4>, std::array<double, 3>>
71 rotation_and_translation =
73 next_node_pose.data(), next_node.gravity_alignment,
74 interpolation_parameter);
76 std::get<1>(rotation_and_translation)) *
77 observation.landmark_to_tracking_transform;
80 void AddLandmarkCostFunctions(
81 const std::map<std::string, LandmarkNode>& landmark_nodes,
82 bool freeze_landmarks,
const MapById<NodeId, NodeSpec2D>& node_data,
83 MapById<NodeId, std::array<double, 3>>* C_nodes,
84 std::map<std::string, CeresPose>* C_landmarks, ceres::Problem* problem) {
85 for (
const auto& landmark_node : landmark_nodes) {
87 if (!landmark_node.second.global_landmark_pose.has_value() &&
91 for (
const auto& observation : landmark_node.second.landmark_observations) {
92 const std::string& landmark_id = landmark_node.first;
93 const auto& begin_of_trajectory =
94 node_data.BeginOfTrajectory(observation.trajectory_id);
96 if (observation.time < begin_of_trajectory->data.time) {
101 node_data.lower_bound(observation.trajectory_id, observation.time);
104 if (next == node_data.EndOfTrajectory(observation.trajectory_id)) {
107 if (next == begin_of_trajectory) {
108 next = std::next(next);
110 auto prev = std::prev(next);
112 std::array<double, 3>* prev_node_pose = &C_nodes->at(prev->id);
113 std::array<double, 3>* next_node_pose = &C_nodes->at(next->id);
114 if (!C_landmarks->count(landmark_id)) {
116 landmark_node.second.global_landmark_pose.has_value()
117 ? landmark_node.second.global_landmark_pose.value()
118 : GetInitialLandmarkPose(observation, prev->data, next->data,
119 *prev_node_pose, *next_node_pose);
120 C_landmarks->emplace(
122 CeresPose(starting_point,
nullptr ,
123 common::make_unique<ceres::QuaternionParameterization>(),
125 if (freeze_landmarks) {
126 problem->SetParameterBlockConstant(
127 C_landmarks->at(landmark_id).translation());
128 problem->SetParameterBlockConstant(
129 C_landmarks->at(landmark_id).rotation());
132 problem->AddResidualBlock(
134 observation, prev->data, next->data),
135 nullptr , prev_node_pose->data(),
136 next_node_pose->data(), C_landmarks->at(landmark_id).rotation(),
137 C_landmarks->at(landmark_id).translation());
145 const proto::OptimizationProblemOptions& options)
148 OptimizationProblem2D::~OptimizationProblem2D() {}
150 void OptimizationProblem2D::AddImuData(
const int trajectory_id,
152 imu_data_.Append(trajectory_id, imu_data);
155 void OptimizationProblem2D::AddOdometryData(
157 odometry_data_.Append(trajectory_id, odometry_data);
160 void OptimizationProblem2D::AddTrajectoryNode(
const int trajectory_id,
162 node_data_.Append(trajectory_id, node_data);
165 void OptimizationProblem2D::InsertTrajectoryNode(
const NodeId& node_id,
167 node_data_.Insert(node_id, node_data);
170 void OptimizationProblem2D::TrimTrajectoryNode(
const NodeId& node_id) {
171 imu_data_.Trim(node_data_, node_id);
172 odometry_data_.Trim(node_data_, node_id);
173 node_data_.Trim(node_id);
176 void OptimizationProblem2D::AddSubmap(
178 submap_data_.Append(trajectory_id,
SubmapSpec2D{global_submap_pose});
181 void OptimizationProblem2D::InsertSubmap(
183 submap_data_.Insert(submap_id,
SubmapSpec2D{global_submap_pose});
186 void OptimizationProblem2D::TrimSubmap(
const SubmapId& submap_id) {
187 submap_data_.Trim(submap_id);
190 void OptimizationProblem2D::SetMaxNumIterations(
191 const int32 max_num_iterations) {
192 options_.mutable_ceres_solver_options()->set_max_num_iterations(
196 void OptimizationProblem2D::Solve(
197 const std::vector<Constraint>& constraints,
198 const std::set<int>& frozen_trajectories,
199 const std::map<std::string, LandmarkNode>& landmark_nodes) {
200 if (node_data_.empty()) {
205 ceres::Problem::Options problem_options;
206 ceres::Problem problem(problem_options);
212 std::map<std::string, CeresPose> C_landmarks;
213 bool first_submap =
true;
214 bool freeze_landmarks = !frozen_trajectories.
empty();
215 for (
const auto& submap_id_data : submap_data_) {
217 frozen_trajectories.count(submap_id_data.id.trajectory_id) != 0;
218 C_submaps.
Insert(submap_id_data.id,
219 FromPose(submap_id_data.data.global_pose));
220 problem.AddParameterBlock(C_submaps.
at(submap_id_data.id).data(), 3);
221 if (first_submap || frozen) {
222 first_submap =
false;
225 problem.SetParameterBlockConstant(C_submaps.
at(submap_id_data.id).data());
228 for (
const auto& node_id_data : node_data_) {
230 frozen_trajectories.count(node_id_data.id.trajectory_id) != 0;
231 C_nodes.
Insert(node_id_data.id,
FromPose(node_id_data.data.global_pose_2d));
232 problem.AddParameterBlock(C_nodes.
at(node_id_data.id).data(), 3);
234 problem.SetParameterBlockConstant(C_nodes.
at(node_id_data.id).data());
238 for (
const Constraint& constraint : constraints) {
239 problem.AddResidualBlock(
242 constraint.tag == Constraint::INTER_SUBMAP
243 ?
new ceres::HuberLoss(
options_.huber_scale())
245 C_submaps.
at(constraint.submap_id).data(),
246 C_nodes.
at(constraint.node_id).data());
249 AddLandmarkCostFunctions(landmark_nodes, freeze_landmarks, node_data_,
250 &C_nodes, &C_landmarks, &problem);
253 for (
auto node_it = node_data_.begin(); node_it != node_data_.end();) {
254 const int trajectory_id = node_it->id.trajectory_id;
255 const auto trajectory_end = node_data_.EndOfTrajectory(trajectory_id);
256 if (frozen_trajectories.count(trajectory_id) != 0) {
257 node_it = trajectory_end;
261 auto prev_node_it = node_it;
262 for (++node_it; node_it != trajectory_end; ++node_it) {
263 const NodeId first_node_id = prev_node_it->id;
264 const NodeSpec2D& first_node_data = prev_node_it->data;
265 prev_node_it = node_it;
266 const NodeId second_node_id = node_it->id;
267 const NodeSpec2D& second_node_data = node_it->data;
274 std::unique_ptr<transform::Rigid3d> relative_odometry =
275 CalculateOdometryBetweenNodes(trajectory_id, first_node_data,
277 if (relative_odometry !=
nullptr) {
278 problem.AddResidualBlock(
280 *relative_odometry,
options_.odometry_translation_weight(),
281 options_.odometry_rotation_weight()}),
282 nullptr , C_nodes.
at(first_node_id).data(),
283 C_nodes.
at(second_node_id).data());
290 problem.AddResidualBlock(
293 options_.local_slam_pose_translation_weight(),
294 options_.local_slam_pose_rotation_weight()}),
295 nullptr , C_nodes.
at(first_node_id).data(),
296 C_nodes.
at(second_node_id).data());
301 ceres::Solver::Summary summary;
305 if (
options_.log_solver_summary()) {
306 LOG(INFO) << summary.FullReport();
310 for (
const auto& C_submap_id_data : C_submaps) {
311 submap_data_.at(C_submap_id_data.id).global_pose =
312 ToPose(C_submap_id_data.data);
314 for (
const auto& C_node_id_data : C_nodes) {
315 node_data_.at(C_node_id_data.id).global_pose_2d =
316 ToPose(C_node_id_data.data);
318 for (
const auto& C_landmark : C_landmarks) {
319 landmark_data_[C_landmark.first] = C_landmark.second.ToRigid();
323 std::unique_ptr<transform::Rigid3d> OptimizationProblem2D::InterpolateOdometry(
325 const auto it = odometry_data_.lower_bound(trajectory_id, time);
326 if (it == odometry_data_.EndOfTrajectory(trajectory_id)) {
329 if (it == odometry_data_.BeginOfTrajectory(trajectory_id)) {
330 if (it->time == time) {
331 return common::make_unique<transform::Rigid3d>(it->pose);
335 const auto prev_it = std::prev(it);
336 return common::make_unique<transform::Rigid3d>(
342 std::unique_ptr<transform::Rigid3d>
343 OptimizationProblem2D::CalculateOdometryBetweenNodes(
344 const int trajectory_id,
const NodeSpec2D& first_node_data,
346 if (odometry_data_.HasTrajectory(trajectory_id)) {
347 const std::unique_ptr<transform::Rigid3d> first_node_odometry =
348 InterpolateOdometry(trajectory_id, first_node_data.
time);
349 const std::unique_ptr<transform::Rigid3d> second_node_odometry =
350 InterpolateOdometry(trajectory_id, second_node_data.
time);
351 if (first_node_odometry !=
nullptr && second_node_odometry !=
nullptr) {
354 first_node_odometry->
inverse() * (*second_node_odometry) *
357 return common::make_unique<transform::Rigid3d>(relative_odometry);
const DataType & at(const IdType &id) const
transform::Rigid2d local_pose_2d
void Insert(const IdType &id, const DataType &data)
UniversalTimeScaleClock::time_point Time
static ceres::CostFunction * CreateAutoDiffCostFunction(const LandmarkObservation &observation, const NodeSpec2D &prev_node, const NodeSpec2D &next_node)
ceres::CostFunction * CreateAutoDiffSpaCostFunction(const PoseGraphInterface::Constraint::Pose &observed_relative_pose)
CeresPose::Data FromPose(const transform::Rigid3d &pose)
OptimizationProblem2D(const optimization::proto::OptimizationProblemOptions &options)
proto::ProbabilityGridRangeDataInserterOptions2D options_
ceres::Solver::Options CreateCeresSolverOptions(const proto::CeresSolverOptions &proto)
std::array< double, 3 > translation
double ToSeconds(const Duration duration)
std::tuple< std::array< T, 4 >, std::array< T, 3 > > InterpolateNodes2D(const T *const prev_node_pose, const Eigen::Quaterniond &prev_node_gravity_alignment, const T *const next_node_pose, const Eigen::Quaterniond &next_node_gravity_alignment, const double interpolation_parameter)
Eigen::Quaterniond gravity_alignment