optimization_problem_3d.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 <iterator>
23 #include <map>
24 #include <memory>
25 #include <string>
26 #include <vector>
27 
28 #include "Eigen/Core"
42 #include "ceres/ceres.h"
43 #include "ceres/jet.h"
44 #include "ceres/rotation.h"
45 #include "glog/logging.h"
46 
47 namespace cartographer {
48 namespace mapping {
49 namespace optimization {
50 namespace {
51 
53 using TrajectoryData =
55 
56 // For odometry.
57 std::unique_ptr<transform::Rigid3d> Interpolate(
58  const sensor::MapByTime<sensor::OdometryData>& map_by_time,
59  const int trajectory_id, const common::Time time) {
60  const auto it = map_by_time.lower_bound(trajectory_id, time);
61  if (it == map_by_time.EndOfTrajectory(trajectory_id)) {
62  return nullptr;
63  }
64  if (it == map_by_time.BeginOfTrajectory(trajectory_id)) {
65  if (it->time == time) {
66  return common::make_unique<transform::Rigid3d>(it->pose);
67  }
68  return nullptr;
69  }
70  const auto prev_it = std::prev(it);
71  return common::make_unique<transform::Rigid3d>(
72  Interpolate(transform::TimestampedTransform{prev_it->time, prev_it->pose},
73  transform::TimestampedTransform{it->time, it->pose}, time)
74  .transform);
75 }
76 
77 // For fixed frame pose.
78 std::unique_ptr<transform::Rigid3d> Interpolate(
79  const sensor::MapByTime<sensor::FixedFramePoseData>& map_by_time,
80  const int trajectory_id, const common::Time time) {
81  const auto it = map_by_time.lower_bound(trajectory_id, time);
82  if (it == map_by_time.EndOfTrajectory(trajectory_id) ||
83  !it->pose.has_value()) {
84  return nullptr;
85  }
86  if (it == map_by_time.BeginOfTrajectory(trajectory_id)) {
87  if (it->time == time) {
88  return common::make_unique<transform::Rigid3d>(it->pose.value());
89  }
90  return nullptr;
91  }
92  const auto prev_it = std::prev(it);
93  if (prev_it->pose.has_value()) {
94  return common::make_unique<transform::Rigid3d>(
95  Interpolate(transform::TimestampedTransform{prev_it->time,
96  prev_it->pose.value()},
97  transform::TimestampedTransform{it->time, it->pose.value()},
98  time)
99  .transform);
100  }
101  return nullptr;
102 }
103 
104 // Selects a trajectory node closest in time to the landmark observation and
105 // applies a relative transform from it.
106 transform::Rigid3d GetInitialLandmarkPose(
107  const LandmarkNode::LandmarkObservation& observation,
108  const NodeSpec3D& prev_node, const NodeSpec3D& next_node,
109  const CeresPose& prev_node_pose, const CeresPose& next_node_pose) {
110  const double interpolation_parameter =
111  common::ToSeconds(observation.time - prev_node.time) /
112  common::ToSeconds(next_node.time - prev_node.time);
113 
114  const std::tuple<std::array<double, 4>, std::array<double, 3>>
115  rotation_and_translation = InterpolateNodes3D(
116  prev_node_pose.rotation(), prev_node_pose.translation(),
117  next_node_pose.rotation(), next_node_pose.translation(),
118  interpolation_parameter);
119  return transform::Rigid3d::FromArrays(std::get<0>(rotation_and_translation),
120  std::get<1>(rotation_and_translation)) *
121  observation.landmark_to_tracking_transform;
122 }
123 
124 void AddLandmarkCostFunctions(
125  const std::map<std::string, LandmarkNode>& landmark_nodes,
126  bool freeze_landmarks, const MapById<NodeId, NodeSpec3D>& node_data,
127  MapById<NodeId, CeresPose>* C_nodes,
128  std::map<std::string, CeresPose>* C_landmarks, ceres::Problem* problem) {
129  for (const auto& landmark_node : landmark_nodes) {
130  // Do not use landmarks that were not optimized for localization.
131  if (!landmark_node.second.global_landmark_pose.has_value() &&
132  freeze_landmarks) {
133  continue;
134  }
135  for (const auto& observation : landmark_node.second.landmark_observations) {
136  const std::string& landmark_id = landmark_node.first;
137  const auto& begin_of_trajectory =
138  node_data.BeginOfTrajectory(observation.trajectory_id);
139  // The landmark observation was made before the trajectory was created.
140  if (observation.time < begin_of_trajectory->data.time) {
141  continue;
142  }
143  // Find the trajectory nodes before and after the landmark observation.
144  auto next =
145  node_data.lower_bound(observation.trajectory_id, observation.time);
146  // The landmark observation was made, but the next trajectory node has
147  // not been added yet.
148  if (next == node_data.EndOfTrajectory(observation.trajectory_id)) {
149  continue;
150  }
151  if (next == begin_of_trajectory) {
152  next = std::next(next);
153  }
154  auto prev = std::prev(next);
155  // Add parameter blocks for the landmark ID if they were not added before.
156  CeresPose* prev_node_pose = &C_nodes->at(prev->id);
157  CeresPose* next_node_pose = &C_nodes->at(next->id);
158  if (!C_landmarks->count(landmark_id)) {
159  const transform::Rigid3d starting_point =
160  landmark_node.second.global_landmark_pose.has_value()
161  ? landmark_node.second.global_landmark_pose.value()
162  : GetInitialLandmarkPose(observation, prev->data, next->data,
163  *prev_node_pose, *next_node_pose);
164  C_landmarks->emplace(
165  landmark_id,
166  CeresPose(starting_point, nullptr /* translation_parametrization */,
167  common::make_unique<ceres::QuaternionParameterization>(),
168  problem));
169  if (freeze_landmarks) {
170  problem->SetParameterBlockConstant(
171  C_landmarks->at(landmark_id).translation());
172  problem->SetParameterBlockConstant(
173  C_landmarks->at(landmark_id).rotation());
174  }
175  }
176  problem->AddResidualBlock(
178  observation, prev->data, next->data),
179  nullptr /* loss function */, prev_node_pose->rotation(),
180  prev_node_pose->translation(), next_node_pose->rotation(),
181  next_node_pose->translation(),
182  C_landmarks->at(landmark_id).rotation(),
183  C_landmarks->at(landmark_id).translation());
184  }
185  }
186 }
187 
188 } // namespace
189 
191  const optimization::proto::OptimizationProblemOptions& options)
192  : options_(options) {}
193 
195 
196 void OptimizationProblem3D::AddImuData(const int trajectory_id,
197  const sensor::ImuData& imu_data) {
198  imu_data_.Append(trajectory_id, imu_data);
199 }
200 
202  const int trajectory_id, const sensor::OdometryData& odometry_data) {
203  odometry_data_.Append(trajectory_id, odometry_data);
204 }
205 
207  const int trajectory_id,
209  fixed_frame_pose_data_.Append(trajectory_id, fixed_frame_pose_data);
210 }
211 
212 void OptimizationProblem3D::AddTrajectoryNode(const int trajectory_id,
213  const NodeSpec3D& node_data) {
214  node_data_.Append(trajectory_id, node_data);
215  trajectory_data_[trajectory_id];
216 }
217 
219  int trajectory_id, const TrajectoryData& trajectory_data) {
220  trajectory_data_[trajectory_id] = trajectory_data;
221 }
222 
224  const NodeSpec3D& node_data) {
225  node_data_.Insert(node_id, node_data);
227 }
228 
230  imu_data_.Trim(node_data_, node_id);
231  odometry_data_.Trim(node_data_, node_id);
232  fixed_frame_pose_data_.Trim(node_data_, node_id);
233  node_data_.Trim(node_id);
234  if (node_data_.SizeOfTrajectoryOrZero(node_id.trajectory_id) == 0) {
235  trajectory_data_.erase(node_id.trajectory_id);
236  }
237 }
238 
240  const int trajectory_id, const transform::Rigid3d& global_submap_pose) {
241  submap_data_.Append(trajectory_id, SubmapSpec3D{global_submap_pose});
242 }
243 
245  const SubmapId& submap_id, const transform::Rigid3d& global_submap_pose) {
246  submap_data_.Insert(submap_id, SubmapSpec3D{global_submap_pose});
247 }
248 
250  submap_data_.Trim(submap_id);
251 }
252 
254  const int32 max_num_iterations) {
255  options_.mutable_ceres_solver_options()->set_max_num_iterations(
256  max_num_iterations);
257 }
258 
260  const std::vector<Constraint>& constraints,
261  const std::set<int>& frozen_trajectories,
262  const std::map<std::string, LandmarkNode>& landmark_nodes) {
263  if (node_data_.empty()) {
264  // Nothing to optimize.
265  return;
266  }
267 
268  ceres::Problem::Options problem_options;
269  ceres::Problem problem(problem_options);
270 
271  const auto translation_parameterization =
272  [this]() -> std::unique_ptr<ceres::LocalParameterization> {
273  return options_.fix_z_in_3d()
274  ? common::make_unique<ceres::SubsetParameterization>(
275  3, std::vector<int>{2})
276  : nullptr;
277  };
278 
279  // Set the starting point.
280  CHECK(!submap_data_.empty());
283  std::map<std::string, CeresPose> C_landmarks;
284  bool first_submap = true;
285  bool freeze_landmarks = !frozen_trajectories.empty();
286  for (const auto& submap_id_data : submap_data_) {
287  const bool frozen =
288  frozen_trajectories.count(submap_id_data.id.trajectory_id) != 0;
289  if (first_submap) {
290  first_submap = false;
291  // Fix the first submap of the first trajectory except for allowing
292  // gravity alignment.
293  C_submaps.Insert(
294  submap_id_data.id,
295  CeresPose(submap_id_data.data.global_pose,
296  translation_parameterization(),
297  common::make_unique<ceres::AutoDiffLocalParameterization<
298  ConstantYawQuaternionPlus, 4, 2>>(),
299  &problem));
300  problem.SetParameterBlockConstant(
301  C_submaps.at(submap_id_data.id).translation());
302  } else {
303  C_submaps.Insert(
304  submap_id_data.id,
305  CeresPose(submap_id_data.data.global_pose,
306  translation_parameterization(),
307  common::make_unique<ceres::QuaternionParameterization>(),
308  &problem));
309  }
310  if (frozen) {
311  problem.SetParameterBlockConstant(
312  C_submaps.at(submap_id_data.id).rotation());
313  problem.SetParameterBlockConstant(
314  C_submaps.at(submap_id_data.id).translation());
315  }
316  }
317  for (const auto& node_id_data : node_data_) {
318  const bool frozen =
319  frozen_trajectories.count(node_id_data.id.trajectory_id) != 0;
320  C_nodes.Insert(
321  node_id_data.id,
322  CeresPose(node_id_data.data.global_pose, translation_parameterization(),
323  common::make_unique<ceres::QuaternionParameterization>(),
324  &problem));
325  if (frozen) {
326  problem.SetParameterBlockConstant(C_nodes.at(node_id_data.id).rotation());
327  problem.SetParameterBlockConstant(
328  C_nodes.at(node_id_data.id).translation());
329  }
330  }
331  // Add cost functions for intra- and inter-submap constraints.
332  for (const Constraint& constraint : constraints) {
333  problem.AddResidualBlock(
335  // Only loop closure constraints should have a loss function.
336  constraint.tag == Constraint::INTER_SUBMAP
337  ? new ceres::HuberLoss(options_.huber_scale())
338  : nullptr /* loss function */,
339  C_submaps.at(constraint.submap_id).rotation(),
340  C_submaps.at(constraint.submap_id).translation(),
341  C_nodes.at(constraint.node_id).rotation(),
342  C_nodes.at(constraint.node_id).translation());
343  }
344  // Add cost functions for landmarks.
345  AddLandmarkCostFunctions(landmark_nodes, freeze_landmarks, node_data_,
346  &C_nodes, &C_landmarks, &problem);
347  // Add constraints based on IMU observations of angular velocities and
348  // linear acceleration.
349  if (!options_.fix_z_in_3d()) {
350  for (auto node_it = node_data_.begin(); node_it != node_data_.end();) {
351  const int trajectory_id = node_it->id.trajectory_id;
352  const auto trajectory_end = node_data_.EndOfTrajectory(trajectory_id);
353  if (frozen_trajectories.count(trajectory_id) != 0) {
354  // We skip frozen trajectories.
355  node_it = trajectory_end;
356  continue;
357  }
358  TrajectoryData& trajectory_data = trajectory_data_.at(trajectory_id);
359 
360  problem.AddParameterBlock(trajectory_data.imu_calibration.data(), 4,
361  new ceres::QuaternionParameterization());
362  CHECK(imu_data_.HasTrajectory(trajectory_id));
363  const auto imu_data = imu_data_.trajectory(trajectory_id);
364  CHECK(imu_data.begin() != imu_data.end());
365 
366  auto imu_it = imu_data.begin();
367  auto prev_node_it = node_it;
368  for (++node_it; node_it != trajectory_end; ++node_it) {
369  const NodeId first_node_id = prev_node_it->id;
370  const NodeSpec3D& first_node_data = prev_node_it->data;
371  prev_node_it = node_it;
372  const NodeId second_node_id = node_it->id;
373  const NodeSpec3D& second_node_data = node_it->data;
374 
375  if (second_node_id.node_index != first_node_id.node_index + 1) {
376  continue;
377  }
378 
379  // Skip IMU data before the node.
380  while (std::next(imu_it) != imu_data.end() &&
381  std::next(imu_it)->time <= first_node_data.time) {
382  ++imu_it;
383  }
384 
385  auto imu_it2 = imu_it;
387  imu_data, first_node_data.time, second_node_data.time, &imu_it);
388  const auto next_node_it = std::next(node_it);
389  if (next_node_it != trajectory_end &&
390  next_node_it->id.node_index == second_node_id.node_index + 1) {
391  const NodeId third_node_id = next_node_it->id;
392  const NodeSpec3D& third_node_data = next_node_it->data;
393  const common::Time first_time = first_node_data.time;
394  const common::Time second_time = second_node_data.time;
395  const common::Time third_time = third_node_data.time;
396  const common::Duration first_duration = second_time - first_time;
397  const common::Duration second_duration = third_time - second_time;
398  const common::Time first_center = first_time + first_duration / 2;
399  const common::Time second_center = second_time + second_duration / 2;
400  const IntegrateImuResult<double> result_to_first_center =
401  IntegrateImu(imu_data, first_time, first_center, &imu_it2);
402  const IntegrateImuResult<double> result_center_to_center =
403  IntegrateImu(imu_data, first_center, second_center, &imu_it2);
404  // 'delta_velocity' is the change in velocity from the point in time
405  // halfway between the first and second poses to halfway between
406  // second and third pose. It is computed from IMU data and still
407  // contains a delta due to gravity. The orientation of this vector is
408  // in the IMU frame at the second pose.
409  const Eigen::Vector3d delta_velocity =
410  (result.delta_rotation.inverse() *
411  result_to_first_center.delta_rotation) *
412  result_center_to_center.delta_velocity;
413  problem.AddResidualBlock(
415  options_.acceleration_weight(), delta_velocity,
416  common::ToSeconds(first_duration),
417  common::ToSeconds(second_duration)),
418  nullptr /* loss function */,
419  C_nodes.at(second_node_id).rotation(),
420  C_nodes.at(first_node_id).translation(),
421  C_nodes.at(second_node_id).translation(),
422  C_nodes.at(third_node_id).translation(),
423  &trajectory_data.gravity_constant,
424  trajectory_data.imu_calibration.data());
425  }
426  problem.AddResidualBlock(
428  options_.rotation_weight(), result.delta_rotation),
429  nullptr /* loss function */, C_nodes.at(first_node_id).rotation(),
430  C_nodes.at(second_node_id).rotation(),
431  trajectory_data.imu_calibration.data());
432  }
433  }
434  }
435 
436  if (options_.fix_z_in_3d()) {
437  // Add penalties for violating odometry (if available) and changes between
438  // consecutive nodes.
439  for (auto node_it = node_data_.begin(); node_it != node_data_.end();) {
440  const int trajectory_id = node_it->id.trajectory_id;
441  const auto trajectory_end = node_data_.EndOfTrajectory(trajectory_id);
442  if (frozen_trajectories.count(trajectory_id) != 0) {
443  node_it = trajectory_end;
444  continue;
445  }
446 
447  auto prev_node_it = node_it;
448  for (++node_it; node_it != trajectory_end; ++node_it) {
449  const NodeId first_node_id = prev_node_it->id;
450  const NodeSpec3D& first_node_data = prev_node_it->data;
451  prev_node_it = node_it;
452  const NodeId second_node_id = node_it->id;
453  const NodeSpec3D& second_node_data = node_it->data;
454 
455  if (second_node_id.node_index != first_node_id.node_index + 1) {
456  continue;
457  }
458 
459  // Add a relative pose constraint based on the odometry (if available).
460  const std::unique_ptr<transform::Rigid3d> relative_odometry =
461  CalculateOdometryBetweenNodes(trajectory_id, first_node_data,
462  second_node_data);
463  if (relative_odometry != nullptr) {
464  problem.AddResidualBlock(
466  *relative_odometry, options_.odometry_translation_weight(),
467  options_.odometry_rotation_weight()}),
468  nullptr /* loss function */, C_nodes.at(first_node_id).rotation(),
469  C_nodes.at(first_node_id).translation(),
470  C_nodes.at(second_node_id).rotation(),
471  C_nodes.at(second_node_id).translation());
472  }
473 
474  // Add a relative pose constraint based on consecutive local SLAM poses.
475  const transform::Rigid3d relative_local_slam_pose =
476  first_node_data.local_pose.inverse() * second_node_data.local_pose;
477  problem.AddResidualBlock(
479  Constraint::Pose{relative_local_slam_pose,
480  options_.local_slam_pose_translation_weight(),
481  options_.local_slam_pose_rotation_weight()}),
482  nullptr /* loss function */, C_nodes.at(first_node_id).rotation(),
483  C_nodes.at(first_node_id).translation(),
484  C_nodes.at(second_node_id).rotation(),
485  C_nodes.at(second_node_id).translation());
486  }
487  }
488  }
489 
490  // Add fixed frame pose constraints.
491  std::map<int, CeresPose> C_fixed_frames;
492  for (auto node_it = node_data_.begin(); node_it != node_data_.end();) {
493  const int trajectory_id = node_it->id.trajectory_id;
494  const auto trajectory_end = node_data_.EndOfTrajectory(trajectory_id);
495  if (!fixed_frame_pose_data_.HasTrajectory(trajectory_id)) {
496  node_it = trajectory_end;
497  continue;
498  }
499 
500  const TrajectoryData& trajectory_data = trajectory_data_.at(trajectory_id);
501  bool fixed_frame_pose_initialized = false;
502  for (; node_it != trajectory_end; ++node_it) {
503  const NodeId node_id = node_it->id;
504  const NodeSpec3D& node_data = node_it->data;
505 
506  const std::unique_ptr<transform::Rigid3d> fixed_frame_pose =
507  Interpolate(fixed_frame_pose_data_, trajectory_id, node_data.time);
508  if (fixed_frame_pose == nullptr) {
509  continue;
510  }
511 
512  const Constraint::Pose constraint_pose{
513  *fixed_frame_pose, options_.fixed_frame_pose_translation_weight(),
514  options_.fixed_frame_pose_rotation_weight()};
515 
516  if (!fixed_frame_pose_initialized) {
517  transform::Rigid3d fixed_frame_pose_in_map;
518  if (trajectory_data.fixed_frame_origin_in_map.has_value()) {
519  fixed_frame_pose_in_map =
520  trajectory_data.fixed_frame_origin_in_map.value();
521  } else {
522  fixed_frame_pose_in_map =
523  node_data.global_pose * constraint_pose.zbar_ij.inverse();
524  }
525  C_fixed_frames.emplace(
526  std::piecewise_construct, std::forward_as_tuple(trajectory_id),
527  std::forward_as_tuple(
529  fixed_frame_pose_in_map.translation(),
530  Eigen::AngleAxisd(
531  transform::GetYaw(fixed_frame_pose_in_map.rotation()),
532  Eigen::Vector3d::UnitZ())),
533  nullptr,
534  common::make_unique<ceres::AutoDiffLocalParameterization<
535  YawOnlyQuaternionPlus, 4, 1>>(),
536  &problem));
537  fixed_frame_pose_initialized = true;
538  }
539 
540  problem.AddResidualBlock(
542  nullptr /* loss function */,
543  C_fixed_frames.at(trajectory_id).rotation(),
544  C_fixed_frames.at(trajectory_id).translation(),
545  C_nodes.at(node_id).rotation(), C_nodes.at(node_id).translation());
546  }
547  }
548  // Solve.
549  ceres::Solver::Summary summary;
550  ceres::Solve(
551  common::CreateCeresSolverOptions(options_.ceres_solver_options()),
552  &problem, &summary);
553  if (options_.log_solver_summary()) {
554  LOG(INFO) << summary.FullReport();
555  for (const auto& trajectory_id_and_data : trajectory_data_) {
556  const int trajectory_id = trajectory_id_and_data.first;
557  const TrajectoryData& trajectory_data = trajectory_id_and_data.second;
558  if (trajectory_id != 0) {
559  LOG(INFO) << "Trajectory " << trajectory_id << ":";
560  }
561  LOG(INFO) << "Gravity was: " << trajectory_data.gravity_constant;
562  const auto& imu_calibration = trajectory_data.imu_calibration;
563  LOG(INFO) << "IMU correction was: "
564  << common::RadToDeg(2. * std::acos(imu_calibration[0]))
565  << " deg (" << imu_calibration[0] << ", " << imu_calibration[1]
566  << ", " << imu_calibration[2] << ", " << imu_calibration[3]
567  << ")";
568  }
569  }
570 
571  // Store the result.
572  for (const auto& C_submap_id_data : C_submaps) {
573  submap_data_.at(C_submap_id_data.id).global_pose =
574  C_submap_id_data.data.ToRigid();
575  }
576  for (const auto& C_node_id_data : C_nodes) {
577  node_data_.at(C_node_id_data.id).global_pose =
578  C_node_id_data.data.ToRigid();
579  }
580  for (const auto& C_fixed_frame : C_fixed_frames) {
581  trajectory_data_.at(C_fixed_frame.first).fixed_frame_origin_in_map =
582  C_fixed_frame.second.ToRigid();
583  }
584  for (const auto& C_landmark : C_landmarks) {
585  landmark_data_[C_landmark.first] = C_landmark.second.ToRigid();
586  }
587 }
588 
589 std::unique_ptr<transform::Rigid3d>
591  const int trajectory_id, const NodeSpec3D& first_node_data,
592  const NodeSpec3D& second_node_data) const {
593  if (odometry_data_.HasTrajectory(trajectory_id)) {
594  const std::unique_ptr<transform::Rigid3d> first_node_odometry =
595  Interpolate(odometry_data_, trajectory_id, first_node_data.time);
596  const std::unique_ptr<transform::Rigid3d> second_node_odometry =
597  Interpolate(odometry_data_, trajectory_id, second_node_data.time);
598  if (first_node_odometry != nullptr && second_node_odometry != nullptr) {
599  const transform::Rigid3d relative_odometry =
600  first_node_odometry->inverse() * (*second_node_odometry);
601  return common::make_unique<transform::Rigid3d>(relative_odometry);
602  }
603  }
604  return nullptr;
605 }
606 
607 } // namespace optimization
608 } // namespace mapping
609 } // namespace cartographer
const sensor::MapByTime< sensor::OdometryData > & odometry_data() const override
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const Eigen::Quaterniond &delta_rotation_imu_frame)
const sensor::MapByTime< sensor::ImuData > & imu_data() const override
void AddFixedFramePoseData(int trajectory_id, const sensor::FixedFramePoseData &fixed_frame_pose_data)
void AddImuData(int trajectory_id, const sensor::ImuData &imu_data) override
std::map< std::string, transform::Rigid3d > landmark_data_
_Unique_if< T >::_Single_object make_unique(Args &&... args)
Definition: make_unique.h:46
bool empty() const
Definition: id.h:361
Rigid3< double > Rigid3d
void Solve(const std::vector< Constraint > &constraints, const std::set< int > &frozen_trajectories, const std::map< std::string, LandmarkNode > &landmark_nodes) override
void AddOdometryData(int trajectory_id, const sensor::OdometryData &odometry_data) override
void AddSubmap(int trajectory_id, const transform::Rigid3d &global_submap_pose) override
const DataType & at(const IdType &id) const
Definition: id.h:311
void AddTrajectoryNode(int trajectory_id, const NodeSpec3D &node_data) override
void Insert(const IdType &id, const DataType &data)
Definition: id.h:280
constexpr double RadToDeg(double rad)
Definition: math.h:58
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
std::unique_ptr< transform::Rigid3d > CalculateOdometryBetweenNodes(int trajectory_id, const NodeSpec3D &first_node_data, const NodeSpec3D &second_node_data) const
T GetYaw(const Eigen::Quaternion< T > &rotation)
Definition: transform.h:43
const std::map< int, PoseGraphInterface::TrajectoryData > & trajectory_data() const
static ceres::CostFunction * CreateAutoDiffCostFunction(const LandmarkObservation &observation, const NodeSpec3D &prev_node, const NodeSpec3D &next_node)
const Quaternion & rotation() const
static Rigid3 FromArrays(const std::array< double, 4 > &rotation, const std::array< double, 3 > &translation)
sensor::MapByTime< sensor::FixedFramePoseData > fixed_frame_pose_data_
OptimizationProblem3D(const optimization::proto::OptimizationProblemOptions &options)
static time_point time
TimestampedTransform Interpolate(const TimestampedTransform &start, const TimestampedTransform &end, const common::Time time)
UniversalTimeScaleClock::duration Duration
Definition: time.h:43
proto::ProbabilityGridRangeDataInserterOptions2D options_
std::map< int, PoseGraphInterface::TrajectoryData > trajectory_data_
const Vector & translation() const
std::tuple< std::array< T, 4 >, std::array< T, 3 > > InterpolateNodes3D(const T *const prev_node_rotation, const T *const prev_node_translation, const T *const next_node_rotation, const T *const next_node_translation, const double interpolation_parameter)
IntegrateImuResult< T > IntegrateImu(const RangeType &imu_data, const Eigen::Transform< T, 3, Eigen::Affine > &linear_acceleration_calibration, const Eigen::Transform< T, 3, Eigen::Affine > &angular_velocity_calibration, const common::Time start_time, const common::Time end_time, IteratorType *const it)
ceres::Solver::Options CreateCeresSolverOptions(const proto::CeresSolverOptions &proto)
const sensor::MapByTime< sensor::FixedFramePoseData > & fixed_frame_pose_data() const
double ToSeconds(const Duration duration)
Definition: time.cc:29
void SetTrajectoryData(int trajectory_id, const PoseGraphInterface::TrajectoryData &trajectory_data)
int32_t int32
Definition: port.h:32
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const Eigen::Vector3d &delta_velocity_imu_frame, const double first_delta_time_seconds, const double second_delta_time_seconds)
void InsertSubmap(const SubmapId &submap_id, const transform::Rigid3d &global_submap_pose) override
void InsertTrajectoryNode(const NodeId &node_id, const NodeSpec3D &node_data) override
optimization::proto::OptimizationProblemOptions options_
static ceres::CostFunction * CreateAutoDiffCostFunction(const PoseGraph::Constraint::Pose &pose)


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