00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/mapping/internal/optimization/optimization_problem_3d.h"
00018
00019 #include <algorithm>
00020 #include <array>
00021 #include <cmath>
00022 #include <iterator>
00023 #include <map>
00024 #include <memory>
00025 #include <string>
00026 #include <vector>
00027
00028 #include "Eigen/Core"
00029 #include "absl/memory/memory.h"
00030 #include "cartographer/common/ceres_solver_options.h"
00031 #include "cartographer/common/math.h"
00032 #include "cartographer/common/time.h"
00033 #include "cartographer/mapping/internal/3d/imu_integration.h"
00034 #include "cartographer/mapping/internal/3d/rotation_parameterization.h"
00035 #include "cartographer/mapping/internal/optimization/ceres_pose.h"
00036 #include "cartographer/mapping/internal/optimization/cost_functions/acceleration_cost_function_3d.h"
00037 #include "cartographer/mapping/internal/optimization/cost_functions/landmark_cost_function_3d.h"
00038 #include "cartographer/mapping/internal/optimization/cost_functions/rotation_cost_function_3d.h"
00039 #include "cartographer/mapping/internal/optimization/cost_functions/spa_cost_function_3d.h"
00040 #include "cartographer/transform/timestamped_transform.h"
00041 #include "cartographer/transform/transform.h"
00042 #include "ceres/ceres.h"
00043 #include "ceres/jet.h"
00044 #include "ceres/rotation.h"
00045 #include "glog/logging.h"
00046
00047 namespace cartographer {
00048 namespace mapping {
00049 namespace optimization {
00050 namespace {
00051
00052 using LandmarkNode = ::cartographer::mapping::PoseGraphInterface::LandmarkNode;
00053 using TrajectoryData =
00054 ::cartographer::mapping::PoseGraphInterface::TrajectoryData;
00055
00056
00057 std::unique_ptr<transform::Rigid3d> Interpolate(
00058 const sensor::MapByTime<sensor::OdometryData>& map_by_time,
00059 const int trajectory_id, const common::Time time) {
00060 const auto it = map_by_time.lower_bound(trajectory_id, time);
00061 if (it == map_by_time.EndOfTrajectory(trajectory_id)) {
00062 return nullptr;
00063 }
00064 if (it == map_by_time.BeginOfTrajectory(trajectory_id)) {
00065 if (it->time == time) {
00066 return absl::make_unique<transform::Rigid3d>(it->pose);
00067 }
00068 return nullptr;
00069 }
00070 const auto prev_it = std::prev(it);
00071 return absl::make_unique<transform::Rigid3d>(
00072 Interpolate(transform::TimestampedTransform{prev_it->time, prev_it->pose},
00073 transform::TimestampedTransform{it->time, it->pose}, time)
00074 .transform);
00075 }
00076
00077
00078 std::unique_ptr<transform::Rigid3d> Interpolate(
00079 const sensor::MapByTime<sensor::FixedFramePoseData>& map_by_time,
00080 const int trajectory_id, const common::Time time) {
00081 const auto it = map_by_time.lower_bound(trajectory_id, time);
00082 if (it == map_by_time.EndOfTrajectory(trajectory_id) ||
00083 !it->pose.has_value()) {
00084 return nullptr;
00085 }
00086 if (it == map_by_time.BeginOfTrajectory(trajectory_id)) {
00087 if (it->time == time) {
00088 return absl::make_unique<transform::Rigid3d>(it->pose.value());
00089 }
00090 return nullptr;
00091 }
00092 const auto prev_it = std::prev(it);
00093 if (prev_it->pose.has_value()) {
00094 return absl::make_unique<transform::Rigid3d>(
00095 Interpolate(transform::TimestampedTransform{prev_it->time,
00096 prev_it->pose.value()},
00097 transform::TimestampedTransform{it->time, it->pose.value()},
00098 time)
00099 .transform);
00100 }
00101 return nullptr;
00102 }
00103
00104
00105
00106 transform::Rigid3d GetInitialLandmarkPose(
00107 const LandmarkNode::LandmarkObservation& observation,
00108 const NodeSpec3D& prev_node, const NodeSpec3D& next_node,
00109 const CeresPose& prev_node_pose, const CeresPose& next_node_pose) {
00110 const double interpolation_parameter =
00111 common::ToSeconds(observation.time - prev_node.time) /
00112 common::ToSeconds(next_node.time - prev_node.time);
00113
00114 const std::tuple<std::array<double, 4>, std::array<double, 3>>
00115 rotation_and_translation = InterpolateNodes3D(
00116 prev_node_pose.rotation(), prev_node_pose.translation(),
00117 next_node_pose.rotation(), next_node_pose.translation(),
00118 interpolation_parameter);
00119 return transform::Rigid3d::FromArrays(std::get<0>(rotation_and_translation),
00120 std::get<1>(rotation_and_translation)) *
00121 observation.landmark_to_tracking_transform;
00122 }
00123
00124 void AddLandmarkCostFunctions(
00125 const std::map<std::string, LandmarkNode>& landmark_nodes,
00126 const MapById<NodeId, NodeSpec3D>& node_data,
00127 MapById<NodeId, CeresPose>* C_nodes,
00128 std::map<std::string, CeresPose>* C_landmarks, ceres::Problem* problem,
00129 double huber_scale) {
00130 for (const auto& landmark_node : landmark_nodes) {
00131
00132 for (const auto& observation : landmark_node.second.landmark_observations) {
00133 const std::string& landmark_id = landmark_node.first;
00134 const auto& begin_of_trajectory =
00135 node_data.BeginOfTrajectory(observation.trajectory_id);
00136
00137 if (observation.time < begin_of_trajectory->data.time) {
00138 continue;
00139 }
00140
00141 auto next =
00142 node_data.lower_bound(observation.trajectory_id, observation.time);
00143
00144
00145 if (next == node_data.EndOfTrajectory(observation.trajectory_id)) {
00146 continue;
00147 }
00148 if (next == begin_of_trajectory) {
00149 next = std::next(next);
00150 }
00151 auto prev = std::prev(next);
00152
00153 CeresPose* prev_node_pose = &C_nodes->at(prev->id);
00154 CeresPose* next_node_pose = &C_nodes->at(next->id);
00155 if (!C_landmarks->count(landmark_id)) {
00156 const transform::Rigid3d starting_point =
00157 landmark_node.second.global_landmark_pose.has_value()
00158 ? landmark_node.second.global_landmark_pose.value()
00159 : GetInitialLandmarkPose(observation, prev->data, next->data,
00160 *prev_node_pose, *next_node_pose);
00161 C_landmarks->emplace(
00162 landmark_id,
00163 CeresPose(starting_point, nullptr ,
00164 absl::make_unique<ceres::QuaternionParameterization>(),
00165 problem));
00166
00167 if (landmark_node.second.frozen) {
00168 problem->SetParameterBlockConstant(
00169 C_landmarks->at(landmark_id).translation());
00170 problem->SetParameterBlockConstant(
00171 C_landmarks->at(landmark_id).rotation());
00172 }
00173 }
00174 problem->AddResidualBlock(
00175 LandmarkCostFunction3D::CreateAutoDiffCostFunction(
00176 observation, prev->data, next->data),
00177 new ceres::HuberLoss(huber_scale), prev_node_pose->rotation(),
00178 prev_node_pose->translation(), next_node_pose->rotation(),
00179 next_node_pose->translation(),
00180 C_landmarks->at(landmark_id).rotation(),
00181 C_landmarks->at(landmark_id).translation());
00182 }
00183 }
00184 }
00185
00186 }
00187
00188 OptimizationProblem3D::OptimizationProblem3D(
00189 const optimization::proto::OptimizationProblemOptions& options)
00190 : options_(options) {}
00191
00192 OptimizationProblem3D::~OptimizationProblem3D() {}
00193
00194 void OptimizationProblem3D::AddImuData(const int trajectory_id,
00195 const sensor::ImuData& imu_data) {
00196 imu_data_.Append(trajectory_id, imu_data);
00197 }
00198
00199 void OptimizationProblem3D::AddOdometryData(
00200 const int trajectory_id, const sensor::OdometryData& odometry_data) {
00201 odometry_data_.Append(trajectory_id, odometry_data);
00202 }
00203
00204 void OptimizationProblem3D::AddFixedFramePoseData(
00205 const int trajectory_id,
00206 const sensor::FixedFramePoseData& fixed_frame_pose_data) {
00207 fixed_frame_pose_data_.Append(trajectory_id, fixed_frame_pose_data);
00208 }
00209
00210 void OptimizationProblem3D::AddTrajectoryNode(const int trajectory_id,
00211 const NodeSpec3D& node_data) {
00212 node_data_.Append(trajectory_id, node_data);
00213 trajectory_data_[trajectory_id];
00214 }
00215
00216 void OptimizationProblem3D::SetTrajectoryData(
00217 int trajectory_id, const TrajectoryData& trajectory_data) {
00218 trajectory_data_[trajectory_id] = trajectory_data;
00219 }
00220
00221 void OptimizationProblem3D::InsertTrajectoryNode(const NodeId& node_id,
00222 const NodeSpec3D& node_data) {
00223 node_data_.Insert(node_id, node_data);
00224 trajectory_data_[node_id.trajectory_id];
00225 }
00226
00227 void OptimizationProblem3D::TrimTrajectoryNode(const NodeId& node_id) {
00228 imu_data_.Trim(node_data_, node_id);
00229 odometry_data_.Trim(node_data_, node_id);
00230 fixed_frame_pose_data_.Trim(node_data_, node_id);
00231 node_data_.Trim(node_id);
00232 if (node_data_.SizeOfTrajectoryOrZero(node_id.trajectory_id) == 0) {
00233 trajectory_data_.erase(node_id.trajectory_id);
00234 }
00235 }
00236
00237 void OptimizationProblem3D::AddSubmap(
00238 const int trajectory_id, const transform::Rigid3d& global_submap_pose) {
00239 submap_data_.Append(trajectory_id, SubmapSpec3D{global_submap_pose});
00240 }
00241
00242 void OptimizationProblem3D::InsertSubmap(
00243 const SubmapId& submap_id, const transform::Rigid3d& global_submap_pose) {
00244 submap_data_.Insert(submap_id, SubmapSpec3D{global_submap_pose});
00245 }
00246
00247 void OptimizationProblem3D::TrimSubmap(const SubmapId& submap_id) {
00248 submap_data_.Trim(submap_id);
00249 }
00250
00251 void OptimizationProblem3D::SetMaxNumIterations(
00252 const int32 max_num_iterations) {
00253 options_.mutable_ceres_solver_options()->set_max_num_iterations(
00254 max_num_iterations);
00255 }
00256
00257 void OptimizationProblem3D::Solve(
00258 const std::vector<Constraint>& constraints,
00259 const std::map<int, PoseGraphInterface::TrajectoryState>&
00260 trajectories_state,
00261 const std::map<std::string, LandmarkNode>& landmark_nodes) {
00262 if (node_data_.empty()) {
00263
00264 return;
00265 }
00266
00267 std::set<int> frozen_trajectories;
00268 for (const auto& it : trajectories_state) {
00269 if (it.second == PoseGraphInterface::TrajectoryState::FROZEN) {
00270 frozen_trajectories.insert(it.first);
00271 }
00272 }
00273
00274 ceres::Problem::Options problem_options;
00275 ceres::Problem problem(problem_options);
00276
00277 const auto translation_parameterization =
00278 [this]() -> std::unique_ptr<ceres::LocalParameterization> {
00279 return options_.fix_z_in_3d()
00280 ? absl::make_unique<ceres::SubsetParameterization>(
00281 3, std::vector<int>{2})
00282 : nullptr;
00283 };
00284
00285
00286 CHECK(!submap_data_.empty());
00287 MapById<SubmapId, CeresPose> C_submaps;
00288 MapById<NodeId, CeresPose> C_nodes;
00289 std::map<std::string, CeresPose> C_landmarks;
00290 bool first_submap = true;
00291 for (const auto& submap_id_data : submap_data_) {
00292 const bool frozen =
00293 frozen_trajectories.count(submap_id_data.id.trajectory_id) != 0;
00294 if (first_submap) {
00295 first_submap = false;
00296
00297
00298 C_submaps.Insert(
00299 submap_id_data.id,
00300 CeresPose(submap_id_data.data.global_pose,
00301 translation_parameterization(),
00302 absl::make_unique<ceres::AutoDiffLocalParameterization<
00303 ConstantYawQuaternionPlus, 4, 2>>(),
00304 &problem));
00305 problem.SetParameterBlockConstant(
00306 C_submaps.at(submap_id_data.id).translation());
00307 } else {
00308 C_submaps.Insert(
00309 submap_id_data.id,
00310 CeresPose(submap_id_data.data.global_pose,
00311 translation_parameterization(),
00312 absl::make_unique<ceres::QuaternionParameterization>(),
00313 &problem));
00314 }
00315 if (frozen) {
00316 problem.SetParameterBlockConstant(
00317 C_submaps.at(submap_id_data.id).rotation());
00318 problem.SetParameterBlockConstant(
00319 C_submaps.at(submap_id_data.id).translation());
00320 }
00321 }
00322 for (const auto& node_id_data : node_data_) {
00323 const bool frozen =
00324 frozen_trajectories.count(node_id_data.id.trajectory_id) != 0;
00325 C_nodes.Insert(
00326 node_id_data.id,
00327 CeresPose(node_id_data.data.global_pose, translation_parameterization(),
00328 absl::make_unique<ceres::QuaternionParameterization>(),
00329 &problem));
00330 if (frozen) {
00331 problem.SetParameterBlockConstant(C_nodes.at(node_id_data.id).rotation());
00332 problem.SetParameterBlockConstant(
00333 C_nodes.at(node_id_data.id).translation());
00334 }
00335 }
00336
00337 for (const Constraint& constraint : constraints) {
00338 problem.AddResidualBlock(
00339 SpaCostFunction3D::CreateAutoDiffCostFunction(constraint.pose),
00340
00341 constraint.tag == Constraint::INTER_SUBMAP
00342 ? new ceres::HuberLoss(options_.huber_scale())
00343 : nullptr ,
00344 C_submaps.at(constraint.submap_id).rotation(),
00345 C_submaps.at(constraint.submap_id).translation(),
00346 C_nodes.at(constraint.node_id).rotation(),
00347 C_nodes.at(constraint.node_id).translation());
00348 }
00349
00350 AddLandmarkCostFunctions(landmark_nodes, node_data_, &C_nodes, &C_landmarks,
00351 &problem, options_.huber_scale());
00352
00353
00354 if (!options_.fix_z_in_3d()) {
00355 for (auto node_it = node_data_.begin(); node_it != node_data_.end();) {
00356 const int trajectory_id = node_it->id.trajectory_id;
00357 const auto trajectory_end = node_data_.EndOfTrajectory(trajectory_id);
00358 if (frozen_trajectories.count(trajectory_id) != 0) {
00359
00360 node_it = trajectory_end;
00361 continue;
00362 }
00363 TrajectoryData& trajectory_data = trajectory_data_.at(trajectory_id);
00364
00365 problem.AddParameterBlock(trajectory_data.imu_calibration.data(), 4,
00366 new ceres::QuaternionParameterization());
00367 if (!options_.use_online_imu_extrinsics_in_3d()) {
00368 problem.SetParameterBlockConstant(
00369 trajectory_data.imu_calibration.data());
00370 }
00371 CHECK(imu_data_.HasTrajectory(trajectory_id));
00372 const auto imu_data = imu_data_.trajectory(trajectory_id);
00373 CHECK(imu_data.begin() != imu_data.end());
00374
00375 auto imu_it = imu_data.begin();
00376 auto prev_node_it = node_it;
00377 for (++node_it; node_it != trajectory_end; ++node_it) {
00378 const NodeId first_node_id = prev_node_it->id;
00379 const NodeSpec3D& first_node_data = prev_node_it->data;
00380 prev_node_it = node_it;
00381 const NodeId second_node_id = node_it->id;
00382 const NodeSpec3D& second_node_data = node_it->data;
00383
00384 if (second_node_id.node_index != first_node_id.node_index + 1) {
00385 continue;
00386 }
00387
00388
00389 while (std::next(imu_it) != imu_data.end() &&
00390 std::next(imu_it)->time <= first_node_data.time) {
00391 ++imu_it;
00392 }
00393
00394 auto imu_it2 = imu_it;
00395 const IntegrateImuResult<double> result = IntegrateImu(
00396 imu_data, first_node_data.time, second_node_data.time, &imu_it);
00397 const auto next_node_it = std::next(node_it);
00398 if (next_node_it != trajectory_end &&
00399 next_node_it->id.node_index == second_node_id.node_index + 1) {
00400 const NodeId third_node_id = next_node_it->id;
00401 const NodeSpec3D& third_node_data = next_node_it->data;
00402 const common::Time first_time = first_node_data.time;
00403 const common::Time second_time = second_node_data.time;
00404 const common::Time third_time = third_node_data.time;
00405 const common::Duration first_duration = second_time - first_time;
00406 const common::Duration second_duration = third_time - second_time;
00407 const common::Time first_center = first_time + first_duration / 2;
00408 const common::Time second_center = second_time + second_duration / 2;
00409 const IntegrateImuResult<double> result_to_first_center =
00410 IntegrateImu(imu_data, first_time, first_center, &imu_it2);
00411 const IntegrateImuResult<double> result_center_to_center =
00412 IntegrateImu(imu_data, first_center, second_center, &imu_it2);
00413
00414
00415
00416
00417
00418 const Eigen::Vector3d delta_velocity =
00419 (result.delta_rotation.inverse() *
00420 result_to_first_center.delta_rotation) *
00421 result_center_to_center.delta_velocity;
00422 problem.AddResidualBlock(
00423 AccelerationCostFunction3D::CreateAutoDiffCostFunction(
00424 options_.acceleration_weight(), delta_velocity,
00425 common::ToSeconds(first_duration),
00426 common::ToSeconds(second_duration)),
00427 nullptr ,
00428 C_nodes.at(second_node_id).rotation(),
00429 C_nodes.at(first_node_id).translation(),
00430 C_nodes.at(second_node_id).translation(),
00431 C_nodes.at(third_node_id).translation(),
00432 &trajectory_data.gravity_constant,
00433 trajectory_data.imu_calibration.data());
00434 }
00435 problem.AddResidualBlock(
00436 RotationCostFunction3D::CreateAutoDiffCostFunction(
00437 options_.rotation_weight(), result.delta_rotation),
00438 nullptr , C_nodes.at(first_node_id).rotation(),
00439 C_nodes.at(second_node_id).rotation(),
00440 trajectory_data.imu_calibration.data());
00441 }
00442 }
00443 }
00444
00445 if (options_.fix_z_in_3d()) {
00446
00447
00448 for (auto node_it = node_data_.begin(); node_it != node_data_.end();) {
00449 const int trajectory_id = node_it->id.trajectory_id;
00450 const auto trajectory_end = node_data_.EndOfTrajectory(trajectory_id);
00451 if (frozen_trajectories.count(trajectory_id) != 0) {
00452 node_it = trajectory_end;
00453 continue;
00454 }
00455
00456 auto prev_node_it = node_it;
00457 for (++node_it; node_it != trajectory_end; ++node_it) {
00458 const NodeId first_node_id = prev_node_it->id;
00459 const NodeSpec3D& first_node_data = prev_node_it->data;
00460 prev_node_it = node_it;
00461 const NodeId second_node_id = node_it->id;
00462 const NodeSpec3D& second_node_data = node_it->data;
00463
00464 if (second_node_id.node_index != first_node_id.node_index + 1) {
00465 continue;
00466 }
00467
00468
00469 const std::unique_ptr<transform::Rigid3d> relative_odometry =
00470 CalculateOdometryBetweenNodes(trajectory_id, first_node_data,
00471 second_node_data);
00472 if (relative_odometry != nullptr) {
00473 problem.AddResidualBlock(
00474 SpaCostFunction3D::CreateAutoDiffCostFunction(Constraint::Pose{
00475 *relative_odometry, options_.odometry_translation_weight(),
00476 options_.odometry_rotation_weight()}),
00477 nullptr , C_nodes.at(first_node_id).rotation(),
00478 C_nodes.at(first_node_id).translation(),
00479 C_nodes.at(second_node_id).rotation(),
00480 C_nodes.at(second_node_id).translation());
00481 }
00482
00483
00484 const transform::Rigid3d relative_local_slam_pose =
00485 first_node_data.local_pose.inverse() * second_node_data.local_pose;
00486 problem.AddResidualBlock(
00487 SpaCostFunction3D::CreateAutoDiffCostFunction(
00488 Constraint::Pose{relative_local_slam_pose,
00489 options_.local_slam_pose_translation_weight(),
00490 options_.local_slam_pose_rotation_weight()}),
00491 nullptr , C_nodes.at(first_node_id).rotation(),
00492 C_nodes.at(first_node_id).translation(),
00493 C_nodes.at(second_node_id).rotation(),
00494 C_nodes.at(second_node_id).translation());
00495 }
00496 }
00497 }
00498
00499
00500 std::map<int, CeresPose> C_fixed_frames;
00501 for (auto node_it = node_data_.begin(); node_it != node_data_.end();) {
00502 const int trajectory_id = node_it->id.trajectory_id;
00503 const auto trajectory_end = node_data_.EndOfTrajectory(trajectory_id);
00504 if (!fixed_frame_pose_data_.HasTrajectory(trajectory_id)) {
00505 node_it = trajectory_end;
00506 continue;
00507 }
00508
00509 const TrajectoryData& trajectory_data = trajectory_data_.at(trajectory_id);
00510 bool fixed_frame_pose_initialized = false;
00511 for (; node_it != trajectory_end; ++node_it) {
00512 const NodeId node_id = node_it->id;
00513 const NodeSpec3D& node_data = node_it->data;
00514
00515 const std::unique_ptr<transform::Rigid3d> fixed_frame_pose =
00516 Interpolate(fixed_frame_pose_data_, trajectory_id, node_data.time);
00517 if (fixed_frame_pose == nullptr) {
00518 continue;
00519 }
00520
00521 const Constraint::Pose constraint_pose{
00522 *fixed_frame_pose, options_.fixed_frame_pose_translation_weight(),
00523 options_.fixed_frame_pose_rotation_weight()};
00524
00525 if (!fixed_frame_pose_initialized) {
00526 transform::Rigid3d fixed_frame_pose_in_map;
00527 if (trajectory_data.fixed_frame_origin_in_map.has_value()) {
00528 fixed_frame_pose_in_map =
00529 trajectory_data.fixed_frame_origin_in_map.value();
00530 } else {
00531 fixed_frame_pose_in_map =
00532 node_data.global_pose * constraint_pose.zbar_ij.inverse();
00533 }
00534 C_fixed_frames.emplace(
00535 std::piecewise_construct, std::forward_as_tuple(trajectory_id),
00536 std::forward_as_tuple(
00537 transform::Rigid3d(
00538 fixed_frame_pose_in_map.translation(),
00539 Eigen::AngleAxisd(
00540 transform::GetYaw(fixed_frame_pose_in_map.rotation()),
00541 Eigen::Vector3d::UnitZ())),
00542 nullptr,
00543 absl::make_unique<ceres::AutoDiffLocalParameterization<
00544 YawOnlyQuaternionPlus, 4, 1>>(),
00545 &problem));
00546 fixed_frame_pose_initialized = true;
00547 }
00548
00549 problem.AddResidualBlock(
00550 SpaCostFunction3D::CreateAutoDiffCostFunction(constraint_pose),
00551 nullptr ,
00552 C_fixed_frames.at(trajectory_id).rotation(),
00553 C_fixed_frames.at(trajectory_id).translation(),
00554 C_nodes.at(node_id).rotation(), C_nodes.at(node_id).translation());
00555 }
00556 }
00557
00558 ceres::Solver::Summary summary;
00559 ceres::Solve(
00560 common::CreateCeresSolverOptions(options_.ceres_solver_options()),
00561 &problem, &summary);
00562 if (options_.log_solver_summary()) {
00563 LOG(INFO) << summary.FullReport();
00564 for (const auto& trajectory_id_and_data : trajectory_data_) {
00565 const int trajectory_id = trajectory_id_and_data.first;
00566 const TrajectoryData& trajectory_data = trajectory_id_and_data.second;
00567 if (trajectory_id != 0) {
00568 LOG(INFO) << "Trajectory " << trajectory_id << ":";
00569 }
00570 LOG(INFO) << "Gravity was: " << trajectory_data.gravity_constant;
00571 const auto& imu_calibration = trajectory_data.imu_calibration;
00572 LOG(INFO) << "IMU correction was: "
00573 << common::RadToDeg(2. *
00574 std::acos(std::abs(imu_calibration[0])))
00575 << " deg (" << imu_calibration[0] << ", " << imu_calibration[1]
00576 << ", " << imu_calibration[2] << ", " << imu_calibration[3]
00577 << ")";
00578 }
00579 }
00580
00581
00582 for (const auto& C_submap_id_data : C_submaps) {
00583 submap_data_.at(C_submap_id_data.id).global_pose =
00584 C_submap_id_data.data.ToRigid();
00585 }
00586 for (const auto& C_node_id_data : C_nodes) {
00587 node_data_.at(C_node_id_data.id).global_pose =
00588 C_node_id_data.data.ToRigid();
00589 }
00590 for (const auto& C_fixed_frame : C_fixed_frames) {
00591 trajectory_data_.at(C_fixed_frame.first).fixed_frame_origin_in_map =
00592 C_fixed_frame.second.ToRigid();
00593 }
00594 for (const auto& C_landmark : C_landmarks) {
00595 landmark_data_[C_landmark.first] = C_landmark.second.ToRigid();
00596 }
00597 }
00598
00599 std::unique_ptr<transform::Rigid3d>
00600 OptimizationProblem3D::CalculateOdometryBetweenNodes(
00601 const int trajectory_id, const NodeSpec3D& first_node_data,
00602 const NodeSpec3D& second_node_data) const {
00603 if (odometry_data_.HasTrajectory(trajectory_id)) {
00604 const std::unique_ptr<transform::Rigid3d> first_node_odometry =
00605 Interpolate(odometry_data_, trajectory_id, first_node_data.time);
00606 const std::unique_ptr<transform::Rigid3d> second_node_odometry =
00607 Interpolate(odometry_data_, trajectory_id, second_node_data.time);
00608 if (first_node_odometry != nullptr && second_node_odometry != nullptr) {
00609 const transform::Rigid3d relative_odometry =
00610 first_node_odometry->inverse() * (*second_node_odometry);
00611 return absl::make_unique<transform::Rigid3d>(relative_odometry);
00612 }
00613 }
00614 return nullptr;
00615 }
00616
00617 }
00618 }
00619 }