42 #include "ceres/ceres.h" 43 #include "ceres/jet.h" 44 #include "ceres/rotation.h" 45 #include "glog/logging.h" 49 namespace optimization {
53 using TrajectoryData =
58 const sensor::MapByTime<sensor::OdometryData>& map_by_time,
60 const auto it = map_by_time.lower_bound(trajectory_id, time);
61 if (it == map_by_time.EndOfTrajectory(trajectory_id)) {
64 if (it == map_by_time.BeginOfTrajectory(trajectory_id)) {
65 if (it->time == time) {
66 return common::make_unique<transform::Rigid3d>(it->pose);
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)
79 const sensor::MapByTime<sensor::FixedFramePoseData>& map_by_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()) {
86 if (it == map_by_time.BeginOfTrajectory(trajectory_id)) {
87 if (it->time == time) {
88 return common::make_unique<transform::Rigid3d>(it->pose.value());
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()},
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 =
114 const std::tuple<std::array<double, 4>, std::array<double, 3>>
116 prev_node_pose.rotation(), prev_node_pose.translation(),
117 next_node_pose.rotation(), next_node_pose.translation(),
118 interpolation_parameter);
120 std::get<1>(rotation_and_translation)) *
121 observation.landmark_to_tracking_transform;
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) {
131 if (!landmark_node.second.global_landmark_pose.has_value() &&
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);
140 if (observation.time < begin_of_trajectory->data.time) {
145 node_data.lower_bound(observation.trajectory_id, observation.time);
148 if (next == node_data.EndOfTrajectory(observation.trajectory_id)) {
151 if (next == begin_of_trajectory) {
152 next = std::next(next);
154 auto prev = std::prev(next);
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)) {
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(
166 CeresPose(starting_point,
nullptr ,
167 common::make_unique<ceres::QuaternionParameterization>(),
169 if (freeze_landmarks) {
170 problem->SetParameterBlockConstant(
171 C_landmarks->at(landmark_id).translation());
172 problem->SetParameterBlockConstant(
173 C_landmarks->at(landmark_id).rotation());
176 problem->AddResidualBlock(
178 observation, prev->data, next->data),
179 nullptr , 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());
191 const optimization::proto::OptimizationProblemOptions& options)
198 imu_data_.Append(trajectory_id, imu_data);
207 const int trajectory_id,
254 const int32 max_num_iterations) {
255 options_.mutable_ceres_solver_options()->set_max_num_iterations(
260 const std::vector<Constraint>& constraints,
261 const std::set<int>& frozen_trajectories,
262 const std::map<std::string, LandmarkNode>& landmark_nodes) {
268 ceres::Problem::Options problem_options;
269 ceres::Problem problem(problem_options);
271 const auto translation_parameterization =
272 [
this]() -> std::unique_ptr<ceres::LocalParameterization> {
274 ? common::make_unique<ceres::SubsetParameterization>(
275 3, std::vector<int>{2})
283 std::map<std::string, CeresPose> C_landmarks;
284 bool first_submap =
true;
285 bool freeze_landmarks = !frozen_trajectories.
empty();
288 frozen_trajectories.count(submap_id_data.id.trajectory_id) != 0;
290 first_submap =
false;
295 CeresPose(submap_id_data.data.global_pose,
296 translation_parameterization(),
300 problem.SetParameterBlockConstant(
301 C_submaps.at(submap_id_data.id).translation());
305 CeresPose(submap_id_data.data.global_pose,
306 translation_parameterization(),
307 common::make_unique<ceres::QuaternionParameterization>(),
311 problem.SetParameterBlockConstant(
312 C_submaps.at(submap_id_data.id).rotation());
313 problem.SetParameterBlockConstant(
314 C_submaps.at(submap_id_data.id).translation());
319 frozen_trajectories.count(node_id_data.id.trajectory_id) != 0;
322 CeresPose(node_id_data.data.global_pose, translation_parameterization(),
323 common::make_unique<ceres::QuaternionParameterization>(),
326 problem.SetParameterBlockConstant(C_nodes.
at(node_id_data.id).rotation());
327 problem.SetParameterBlockConstant(
328 C_nodes.
at(node_id_data.id).translation());
332 for (
const Constraint& constraint : constraints) {
333 problem.AddResidualBlock(
337 ?
new ceres::HuberLoss(
options_.huber_scale())
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());
345 AddLandmarkCostFunctions(landmark_nodes, freeze_landmarks, node_data_,
346 &C_nodes, &C_landmarks, &problem);
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) {
355 node_it = trajectory_end;
360 problem.AddParameterBlock(trajectory_data.imu_calibration.data(), 4,
361 new ceres::QuaternionParameterization());
362 CHECK(
imu_data_.HasTrajectory(trajectory_id));
364 CHECK(imu_data.begin() != imu_data.end());
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;
380 while (std::next(imu_it) != imu_data.end() &&
381 std::next(imu_it)->time <= first_node_data.
time) {
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;
398 const common::Time first_center = first_time + first_duration / 2;
399 const common::Time second_center = second_time + second_duration / 2;
401 IntegrateImu(imu_data, first_time, first_center, &imu_it2);
403 IntegrateImu(imu_data, first_center, second_center, &imu_it2);
409 const Eigen::Vector3d delta_velocity =
413 problem.AddResidualBlock(
415 options_.acceleration_weight(), delta_velocity,
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());
426 problem.AddResidualBlock(
429 nullptr , C_nodes.
at(first_node_id).rotation(),
430 C_nodes.
at(second_node_id).rotation(),
431 trajectory_data.imu_calibration.data());
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;
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;
460 const std::unique_ptr<transform::Rigid3d> relative_odometry =
463 if (relative_odometry !=
nullptr) {
464 problem.AddResidualBlock(
466 *relative_odometry,
options_.odometry_translation_weight(),
467 options_.odometry_rotation_weight()}),
468 nullptr , 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());
477 problem.AddResidualBlock(
480 options_.local_slam_pose_translation_weight(),
481 options_.local_slam_pose_rotation_weight()}),
482 nullptr , 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());
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);
496 node_it = trajectory_end;
501 bool fixed_frame_pose_initialized =
false;
502 for (; node_it != trajectory_end; ++node_it) {
503 const NodeId node_id = node_it->id;
506 const std::unique_ptr<transform::Rigid3d> fixed_frame_pose =
508 if (fixed_frame_pose ==
nullptr) {
513 *fixed_frame_pose,
options_.fixed_frame_pose_translation_weight(),
514 options_.fixed_frame_pose_rotation_weight()};
516 if (!fixed_frame_pose_initialized) {
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();
522 fixed_frame_pose_in_map =
525 C_fixed_frames.emplace(
526 std::piecewise_construct, std::forward_as_tuple(trajectory_id),
527 std::forward_as_tuple(
532 Eigen::Vector3d::UnitZ())),
537 fixed_frame_pose_initialized =
true;
540 problem.AddResidualBlock(
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());
549 ceres::Solver::Summary summary;
553 if (
options_.log_solver_summary()) {
554 LOG(INFO) << summary.FullReport();
556 const int trajectory_id = trajectory_id_and_data.first;
558 if (trajectory_id != 0) {
559 LOG(INFO) <<
"Trajectory " << trajectory_id <<
":";
561 LOG(INFO) <<
"Gravity was: " << trajectory_data.gravity_constant;
562 const auto& imu_calibration = trajectory_data.imu_calibration;
563 LOG(INFO) <<
"IMU correction was: " 565 <<
" deg (" << imu_calibration[0] <<
", " << imu_calibration[1]
566 <<
", " << imu_calibration[2] <<
", " << imu_calibration[3]
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();
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();
580 for (
const auto& C_fixed_frame : C_fixed_frames) {
582 C_fixed_frame.second.ToRigid();
584 for (
const auto& C_landmark : C_landmarks) {
589 std::unique_ptr<transform::Rigid3d>
591 const int trajectory_id,
const NodeSpec3D& first_node_data,
594 const std::unique_ptr<transform::Rigid3d> first_node_odometry =
596 const std::unique_ptr<transform::Rigid3d> second_node_odometry =
598 if (first_node_odometry !=
nullptr && second_node_odometry !=
nullptr) {
600 first_node_odometry->
inverse() * (*second_node_odometry);
601 return common::make_unique<transform::Rigid3d>(relative_odometry);
transform::Rigid3d global_pose
const sensor::MapByTime< sensor::OdometryData > & odometry_data() const override
Eigen::Quaternion< T > delta_rotation
sensor::MapByTime< sensor::ImuData > imu_data_
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const Eigen::Quaterniond &delta_rotation_imu_frame)
MapById< NodeId, NodeSpec3D > node_data_
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)
sensor::MapByTime< sensor::OdometryData > odometry_data_
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
void AddTrajectoryNode(int trajectory_id, const NodeSpec3D &node_data) override
void Insert(const IdType &id, const DataType &data)
constexpr double RadToDeg(double rad)
UniversalTimeScaleClock::time_point Time
std::unique_ptr< transform::Rigid3d > CalculateOdometryBetweenNodes(int trajectory_id, const NodeSpec3D &first_node_data, const NodeSpec3D &second_node_data) const
const std::map< int, PoseGraphInterface::TrajectoryData > & trajectory_data() const
static ceres::CostFunction * CreateAutoDiffCostFunction(const LandmarkObservation &observation, const NodeSpec3D &prev_node, const NodeSpec3D &next_node)
sensor::MapByTime< sensor::FixedFramePoseData > fixed_frame_pose_data_
OptimizationProblem3D(const optimization::proto::OptimizationProblemOptions &options)
void TrimTrajectoryNode(const NodeId &node_id) override
UniversalTimeScaleClock::duration Duration
proto::ProbabilityGridRangeDataInserterOptions2D options_
std::map< int, PoseGraphInterface::TrajectoryData > trajectory_data_
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)
MapById< SubmapId, SubmapSpec3D > submap_data_
ceres::Solver::Options CreateCeresSolverOptions(const proto::CeresSolverOptions &proto)
const sensor::MapByTime< sensor::FixedFramePoseData > & fixed_frame_pose_data() const
double ToSeconds(const Duration duration)
void SetTrajectoryData(int trajectory_id, const PoseGraphInterface::TrajectoryData &trajectory_data)
void SetMaxNumIterations(int32 max_num_iterations) override
void TrimSubmap(const SubmapId &submap_id) override
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)
transform::Rigid3d local_pose
void InsertSubmap(const SubmapId &submap_id, const transform::Rigid3d &global_submap_pose) override
Eigen::Matrix< T, 3, 1 > delta_velocity
void InsertTrajectoryNode(const NodeId &node_id, const NodeSpec3D &node_data) override
optimization::proto::OptimizationProblemOptions options_
static ceres::CostFunction * CreateAutoDiffCostFunction(const PoseGraph::Constraint::Pose &pose)
PoseGraphInterface::Constraint Constraint