37 #include "ceres/ceres.h"    38 #include "ceres/jet.h"    39 #include "ceres/rotation.h"    40 #include "glog/logging.h"    43 namespace mapping_3d {
    44 namespace sparse_pose_graph {
    48 struct ConstantYawQuaternionPlus {
    50   bool operator()(
const T* x, 
const T* delta, T* x_plus_delta)
 const {
    53     const T sin_delta_over_delta =
    54         delta_norm < 1e-6 ? T(1.) : ceres::sin(delta_norm) / delta_norm;
    56     q_delta[0] = delta_norm < 1e-6 ? T(1.) : ceres::cos(delta_norm);
    57     q_delta[1] = sin_delta_over_delta * delta[0];
    58     q_delta[2] = sin_delta_over_delta * delta[1];
    66     ceres::QuaternionProduct(x, q_delta, x_plus_delta);
    74     const mapping::sparse_pose_graph::proto::OptimizationProblemOptions&
    77     : 
options_(options), fix_z_(fix_z) {}
    83                                      const Eigen::Vector3d& linear_acceleration,
    84                                      const Eigen::Vector3d& angular_velocity) {
    85   CHECK_GE(trajectory_id, 0);
    87       std::max(
imu_data_.size(), 
static_cast<size_t>(trajectory_id) + 1));
    89       ImuData{
time, linear_acceleration, angular_velocity});
    95   CHECK_GE(trajectory_id, 0);
    97       std::max(
node_data_.size(), 
static_cast<size_t>(trajectory_id) + 1));
   103   CHECK_GE(trajectory_id, 0);
   105       std::max(
submap_data_.size(), 
static_cast<size_t>(trajectory_id) + 1));
   110   options_.mutable_ceres_solver_options()->set_max_num_iterations(
   120   ceres::Problem::Options problem_options;
   121   ceres::Problem problem(problem_options);
   123   const auto translation_parameterization =
   124       [
this]() -> std::unique_ptr<ceres::LocalParameterization> {
   126                ? common::make_unique<ceres::SubsetParameterization>(
   127                      3, std::vector<int>{2})
   135   std::vector<std::deque<CeresPose>> C_submaps(
submap_data_.size());
   136   std::vector<std::deque<CeresPose>> C_nodes(
node_data_.size());
   137   for (
size_t trajectory_id = 0; trajectory_id != 
submap_data_.size();
   139     for (
size_t submap_index = 0;
   140          submap_index != 
submap_data_[trajectory_id].size(); ++submap_index) {
   141       if (trajectory_id == 0 && submap_index == 0) {
   143         C_submaps[trajectory_id].emplace_back(
   146                 ConstantYawQuaternionPlus, 4, 2>>(),
   148         problem.SetParameterBlockConstant(
   149             C_submaps[trajectory_id].back().translation());
   151         C_submaps[trajectory_id].emplace_back(
   153             translation_parameterization(),
   154             common::make_unique<ceres::QuaternionParameterization>(), &problem);
   158   for (
size_t trajectory_id = 0; trajectory_id != 
node_data_.size();
   160     for (
size_t node_index = 0; node_index != 
node_data_[trajectory_id].size();
   162       C_nodes[trajectory_id].emplace_back(
   163           node_data_[trajectory_id][node_index].point_cloud_pose,
   164           translation_parameterization(),
   165           common::make_unique<ceres::QuaternionParameterization>(), &problem);
   170   for (
const Constraint& constraint : constraints) {
   171     problem.AddResidualBlock(
   172         new ceres::AutoDiffCostFunction<SpaCostFunction, 6, 4, 3, 4, 3>(
   176             ? 
new ceres::HuberLoss(
options_.huber_scale())
   178         C_submaps.at(constraint.submap_id.trajectory_id)
   179             .at(constraint.submap_id.submap_index)
   181         C_submaps.at(constraint.submap_id.trajectory_id)
   182             .at(constraint.submap_id.submap_index)
   184         C_nodes.at(constraint.node_id.trajectory_id)
   185             .at(constraint.node_id.node_index)
   187         C_nodes.at(constraint.node_id.trajectory_id)
   188             .at(constraint.node_id.node_index)
   194   for (
size_t trajectory_id = 0; trajectory_id != 
node_data_.size();
   196     const std::deque<ImuData>& imu_data = 
imu_data_.at(trajectory_id);
   197     CHECK(!imu_data.empty());
   200     CHECK(!node_data.empty());
   203     auto it = imu_data.cbegin();
   204     while ((it + 1) != imu_data.cend() && (it + 1)->
time <= node_data[0].
time) {
   208     for (
size_t node_index = 1; node_index < node_data.size(); ++node_index) {
   212                        node_data[node_index].time, &it);
   213       if (node_index + 1 < node_data.size()) {
   214         const common::Time first_time = node_data[node_index - 1].time;
   215         const common::Time second_time = node_data[node_index].time;
   216         const common::Time third_time = node_data[node_index + 1].time;
   219         const common::Time first_center = first_time + first_duration / 2;
   220         const common::Time second_center = second_time + second_duration / 2;
   224             IntegrateImu(imu_data, first_center, second_center, &it2);
   230         const Eigen::Vector3d delta_velocity =
   234         problem.AddResidualBlock(
   238                     options_.acceleration_weight(), delta_velocity,
   241             nullptr, C_nodes[trajectory_id].at(node_index).rotation(),
   242             C_nodes[trajectory_id].at(node_index - 1).translation(),
   243             C_nodes[trajectory_id].at(node_index).translation(),
   244             C_nodes[trajectory_id].at(node_index + 1).translation(),
   247       problem.AddResidualBlock(
   248           new ceres::AutoDiffCostFunction<RotationCostFunction, 3, 4, 4>(
   251           nullptr, C_nodes[trajectory_id].at(node_index - 1).rotation(),
   252           C_nodes[trajectory_id].at(node_index).rotation());
   257   ceres::Solver::Summary summary;
   262   if (
options_.log_solver_summary()) {
   263     LOG(INFO) << summary.FullReport();
   268   for (
size_t trajectory_id = 0; trajectory_id != 
submap_data_.size();
   270     for (
size_t submap_index = 0;
   271          submap_index != 
submap_data_[trajectory_id].size(); ++submap_index) {
   273           C_submaps[trajectory_id][submap_index].ToRigid();
   276   for (
size_t trajectory_id = 0; trajectory_id != 
node_data_.size();
   278     for (
size_t node_index = 0; node_index != 
node_data_[trajectory_id].size();
   280       node_data_[trajectory_id][node_index].point_cloud_pose =
   281           C_nodes[trajectory_id][node_index].ToRigid();
 
proto::RangeDataInserterOptions options_
std::vector< std::deque< ImuData > > imu_data_
const std::vector< std::vector< NodeData > > & node_data() const 
std::vector< std::vector< NodeData > > node_data_
const std::vector< std::vector< SubmapData > > & submap_data() const 
std::vector< std::vector< SubmapData > > submap_data_
void AddImuData(int trajectory_id, common::Time time, const Eigen::Vector3d &linear_acceleration, const Eigen::Vector3d &angular_velocity)
void Solve(const std::vector< Constraint > &constraints)
UniversalTimeScaleClock::time_point Time
OptimizationProblem(const mapping::sparse_pose_graph::proto::OptimizationProblemOptions &options, FixZ fix_z)
void AddSubmap(int trajectory_id, const transform::Rigid3d &submap_pose)
void SetMaxNumIterations(int32 max_num_iterations)
Eigen::Matrix< T, 3, 1 > delta_velocity
UniversalTimeScaleClock::duration Duration
void AddTrajectoryNode(int trajectory_id, common::Time time, const transform::Rigid3d &point_cloud_pose)
ceres::Solver::Options CreateCeresSolverOptions(const proto::CeresSolverOptions &proto)
double ToSeconds(const Duration duration)
Eigen::Quaternion< T > delta_rotation
mapping::sparse_pose_graph::proto::OptimizationProblemOptions options_
_Unique_if< T >::_Single_object make_unique(Args &&...args)
IntegrateImuResult< double > IntegrateImu(const std::deque< ImuData > &imu_data, const common::Time start_time, const common::Time end_time, std::deque< ImuData >::const_iterator *it)