optimization_problem_2d.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
19 #include <algorithm>
20 #include <array>
21 #include <cmath>
22 #include <map>
23 #include <memory>
24 #include <string>
25 #include <vector>
26 
35 #include "ceres/ceres.h"
36 #include "glog/logging.h"
37 
38 namespace cartographer {
39 namespace mapping {
40 namespace optimization {
41 namespace {
42 
43 using ::cartographer::mapping::optimization::CeresPose;
45 
46 // Converts a pose into the 3 optimization variable format used for Ceres:
47 // translation in x and y, followed by the rotation angle representing the
48 // orientation.
49 std::array<double, 3> FromPose(const transform::Rigid2d& pose) {
50  return {{pose.translation().x(), pose.translation().y(),
51  pose.normalized_angle()}};
52 }
53 
54 // Converts a pose as represented for Ceres back to an transform::Rigid2d pose.
55 transform::Rigid2d ToPose(const std::array<double, 3>& values) {
56  return transform::Rigid2d({values[0], values[1]}, values[2]);
57 }
58 
59 // Selects a trajectory node closest in time to the landmark observation and
60 // applies a relative transform from it.
61 transform::Rigid3d GetInitialLandmarkPose(
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 =
67  common::ToSeconds(observation.time - prev_node.time) /
68  common::ToSeconds(next_node.time - prev_node.time);
69 
70  const std::tuple<std::array<double, 4>, std::array<double, 3>>
71  rotation_and_translation =
72  InterpolateNodes2D(prev_node_pose.data(), prev_node.gravity_alignment,
73  next_node_pose.data(), next_node.gravity_alignment,
74  interpolation_parameter);
75  return transform::Rigid3d::FromArrays(std::get<0>(rotation_and_translation),
76  std::get<1>(rotation_and_translation)) *
77  observation.landmark_to_tracking_transform;
78 }
79 
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) {
86  // Do not use landmarks that were not optimized for localization.
87  if (!landmark_node.second.global_landmark_pose.has_value() &&
88  freeze_landmarks) {
89  continue;
90  }
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);
95  // The landmark observation was made before the trajectory was created.
96  if (observation.time < begin_of_trajectory->data.time) {
97  continue;
98  }
99  // Find the trajectory nodes before and after the landmark observation.
100  auto next =
101  node_data.lower_bound(observation.trajectory_id, observation.time);
102  // The landmark observation was made, but the next trajectory node has
103  // not been added yet.
104  if (next == node_data.EndOfTrajectory(observation.trajectory_id)) {
105  continue;
106  }
107  if (next == begin_of_trajectory) {
108  next = std::next(next);
109  }
110  auto prev = std::prev(next);
111  // Add parameter blocks for the landmark ID if they were not added before.
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)) {
115  const transform::Rigid3d starting_point =
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(
121  landmark_id,
122  CeresPose(starting_point, nullptr /* translation_parametrization */,
123  common::make_unique<ceres::QuaternionParameterization>(),
124  problem));
125  if (freeze_landmarks) {
126  problem->SetParameterBlockConstant(
127  C_landmarks->at(landmark_id).translation());
128  problem->SetParameterBlockConstant(
129  C_landmarks->at(landmark_id).rotation());
130  }
131  }
132  problem->AddResidualBlock(
134  observation, prev->data, next->data),
135  nullptr /* loss function */, prev_node_pose->data(),
136  next_node_pose->data(), C_landmarks->at(landmark_id).rotation(),
137  C_landmarks->at(landmark_id).translation());
138  }
139  }
140 }
141 
142 } // namespace
143 
145  const proto::OptimizationProblemOptions& options)
146  : options_(options) {}
147 
148 OptimizationProblem2D::~OptimizationProblem2D() {}
149 
150 void OptimizationProblem2D::AddImuData(const int trajectory_id,
151  const sensor::ImuData& imu_data) {
152  imu_data_.Append(trajectory_id, imu_data);
153 }
154 
155 void OptimizationProblem2D::AddOdometryData(
156  const int trajectory_id, const sensor::OdometryData& odometry_data) {
157  odometry_data_.Append(trajectory_id, odometry_data);
158 }
159 
160 void OptimizationProblem2D::AddTrajectoryNode(const int trajectory_id,
161  const NodeSpec2D& node_data) {
162  node_data_.Append(trajectory_id, node_data);
163 }
164 
165 void OptimizationProblem2D::InsertTrajectoryNode(const NodeId& node_id,
166  const NodeSpec2D& node_data) {
167  node_data_.Insert(node_id, node_data);
168 }
169 
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);
174 }
175 
176 void OptimizationProblem2D::AddSubmap(
177  const int trajectory_id, const transform::Rigid2d& global_submap_pose) {
178  submap_data_.Append(trajectory_id, SubmapSpec2D{global_submap_pose});
179 }
180 
181 void OptimizationProblem2D::InsertSubmap(
182  const SubmapId& submap_id, const transform::Rigid2d& global_submap_pose) {
183  submap_data_.Insert(submap_id, SubmapSpec2D{global_submap_pose});
184 }
185 
186 void OptimizationProblem2D::TrimSubmap(const SubmapId& submap_id) {
187  submap_data_.Trim(submap_id);
188 }
189 
190 void OptimizationProblem2D::SetMaxNumIterations(
191  const int32 max_num_iterations) {
192  options_.mutable_ceres_solver_options()->set_max_num_iterations(
193  max_num_iterations);
194 }
195 
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()) {
201  // Nothing to optimize.
202  return;
203  }
204 
205  ceres::Problem::Options problem_options;
206  ceres::Problem problem(problem_options);
207 
208  // Set the starting point.
209  // TODO(hrapp): Move ceres data into SubmapSpec.
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_) {
216  const bool frozen =
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;
223  // Fix the pose of the first submap or all submaps of a frozen
224  // trajectory.
225  problem.SetParameterBlockConstant(C_submaps.at(submap_id_data.id).data());
226  }
227  }
228  for (const auto& node_id_data : node_data_) {
229  const bool frozen =
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);
233  if (frozen) {
234  problem.SetParameterBlockConstant(C_nodes.at(node_id_data.id).data());
235  }
236  }
237  // Add cost functions for intra- and inter-submap constraints.
238  for (const Constraint& constraint : constraints) {
239  problem.AddResidualBlock(
240  CreateAutoDiffSpaCostFunction(constraint.pose),
241  // Only loop closure constraints should have a loss function.
242  constraint.tag == Constraint::INTER_SUBMAP
243  ? new ceres::HuberLoss(options_.huber_scale())
244  : nullptr,
245  C_submaps.at(constraint.submap_id).data(),
246  C_nodes.at(constraint.node_id).data());
247  }
248  // Add cost functions for landmarks.
249  AddLandmarkCostFunctions(landmark_nodes, freeze_landmarks, node_data_,
250  &C_nodes, &C_landmarks, &problem);
251  // Add penalties for violating odometry or changes between consecutive nodes
252  // if odometry is not available.
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;
258  continue;
259  }
260 
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;
268 
269  if (second_node_id.node_index != first_node_id.node_index + 1) {
270  continue;
271  }
272 
273  // Add a relative pose constraint based on the odometry (if available).
274  std::unique_ptr<transform::Rigid3d> relative_odometry =
275  CalculateOdometryBetweenNodes(trajectory_id, first_node_data,
276  second_node_data);
277  if (relative_odometry != nullptr) {
278  problem.AddResidualBlock(
280  *relative_odometry, options_.odometry_translation_weight(),
281  options_.odometry_rotation_weight()}),
282  nullptr /* loss function */, C_nodes.at(first_node_id).data(),
283  C_nodes.at(second_node_id).data());
284  }
285 
286  // Add a relative pose constraint based on consecutive local SLAM poses.
287  const transform::Rigid3d relative_local_slam_pose =
288  transform::Embed3D(first_node_data.local_pose_2d.inverse() *
289  second_node_data.local_pose_2d);
290  problem.AddResidualBlock(
292  Constraint::Pose{relative_local_slam_pose,
293  options_.local_slam_pose_translation_weight(),
294  options_.local_slam_pose_rotation_weight()}),
295  nullptr /* loss function */, C_nodes.at(first_node_id).data(),
296  C_nodes.at(second_node_id).data());
297  }
298  }
299 
300  // Solve.
301  ceres::Solver::Summary summary;
302  ceres::Solve(
303  common::CreateCeresSolverOptions(options_.ceres_solver_options()),
304  &problem, &summary);
305  if (options_.log_solver_summary()) {
306  LOG(INFO) << summary.FullReport();
307  }
308 
309  // Store the result.
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);
313  }
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);
317  }
318  for (const auto& C_landmark : C_landmarks) {
319  landmark_data_[C_landmark.first] = C_landmark.second.ToRigid();
320  }
321 }
322 
323 std::unique_ptr<transform::Rigid3d> OptimizationProblem2D::InterpolateOdometry(
324  const int trajectory_id, const common::Time time) const {
325  const auto it = odometry_data_.lower_bound(trajectory_id, time);
326  if (it == odometry_data_.EndOfTrajectory(trajectory_id)) {
327  return nullptr;
328  }
329  if (it == odometry_data_.BeginOfTrajectory(trajectory_id)) {
330  if (it->time == time) {
331  return common::make_unique<transform::Rigid3d>(it->pose);
332  }
333  return nullptr;
334  }
335  const auto prev_it = std::prev(it);
336  return common::make_unique<transform::Rigid3d>(
337  Interpolate(transform::TimestampedTransform{prev_it->time, prev_it->pose},
338  transform::TimestampedTransform{it->time, it->pose}, time)
339  .transform);
340 }
341 
342 std::unique_ptr<transform::Rigid3d>
343 OptimizationProblem2D::CalculateOdometryBetweenNodes(
344  const int trajectory_id, const NodeSpec2D& first_node_data,
345  const NodeSpec2D& second_node_data) const {
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) {
352  transform::Rigid3d relative_odometry =
354  first_node_odometry->inverse() * (*second_node_odometry) *
356  second_node_data.gravity_alignment.inverse());
357  return common::make_unique<transform::Rigid3d>(relative_odometry);
358  }
359  }
360  return nullptr;
361 }
362 
363 } // namespace optimization
364 } // namespace mapping
365 } // namespace cartographer
static Rigid3 Rotation(const AngleAxis &angle_axis)
bool empty() const
Definition: id.h:361
Rigid3< double > Rigid3d
const DataType & at(const IdType &id) const
Definition: id.h:311
Rigid3< T > Embed3D(const Rigid2< T > &transform)
Definition: transform.h:110
void Insert(const IdType &id, const DataType &data)
Definition: id.h:280
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
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)
Definition: ceres_pose.cc:23
static Rigid3 FromArrays(const std::array< double, 4 > &rotation, const std::array< double, 3 > &translation)
OptimizationProblem2D(const optimization::proto::OptimizationProblemOptions &options)
Rigid2< double > Rigid2d
TimestampedTransform Interpolate(const TimestampedTransform &start, const TimestampedTransform &end, const common::Time time)
proto::ProbabilityGridRangeDataInserterOptions2D options_
ceres::Solver::Options CreateCeresSolverOptions(const proto::CeresSolverOptions &proto)
double ToSeconds(const Duration duration)
Definition: time.cc:29
int32_t int32
Definition: port.h:32
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)
transform::Rigid3d pose


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58