26 #include "glog/logging.h"    27 #include "gmock/gmock.h"    30 namespace mapping_3d {
    31 namespace sparse_pose_graph {
    34 class OptimizationProblemTest : 
public ::testing::Test {
    36   OptimizationProblemTest()
    40   mapping::sparse_pose_graph::proto::OptimizationProblemOptions
    44           acceleration_weight = 1e-4,    45           rotation_weight = 1e-2,    47           consecutive_scan_translation_penalty_factor = 1e-2,    48           consecutive_scan_rotation_penalty_factor = 1e-2,    49           log_solver_summary = true,    50           ceres_solver_options = {    51             use_nonmonotonic_steps = false,    52             max_num_iterations = 200,    57         parameter_dictionary.get());
    61                                      double rotation_size) {
    62     std::uniform_real_distribution<double> translation_distribution(
    63         -translation_size, translation_size);
    64     const double x = translation_distribution(
rng_);
    65     const double y = translation_distribution(
rng_);
    66     const double z = translation_distribution(
rng_);
    67     std::uniform_real_distribution<double> rotation_distribution(-rotation_size,
    69     const double rx = rotation_distribution(
rng_);
    70     const double ry = rotation_distribution(
rng_);
    71     const double rz = rotation_distribution(
rng_);
    74                                   Eigen::Vector3d(rx, ry, rz)));
    78                                             double rotation_size) {
    79     std::uniform_real_distribution<double> translation_distribution(
    80         -translation_size, translation_size);
    81     const double x = translation_distribution(
rng_);
    82     const double y = translation_distribution(
rng_);
    83     const double z = translation_distribution(
rng_);
    84     std::uniform_real_distribution<double> rotation_distribution(-rotation_size,
    86     const double rz = rotation_distribution(
rng_);
    89                                   Eigen::Vector3d(0., 0., rz)));
    98   const Eigen::Quaterniond noisy_rotation(noise.rotation() *
    99                                           transform.rotation());
   104 TEST_F(OptimizationProblemTest, ReducesNoise) {
   105   constexpr 
int kNumNodes = 100;
   108       Eigen::AngleAxisd(M_PI, Eigen::Vector3d::UnitZ()));
   109   const int kTrajectoryId = 0;
   115   std::vector<NoisyNode> test_data;
   116   for (
int j = 0; j != kNumNodes; ++j) {
   118         NoisyNode{RandomTransform(10., 3.), RandomYawOnlyTransform(0.2, 0.3)});
   122   for (
const NoisyNode& node : test_data) {
   124         AddNoise(node.ground_truth_pose, node.noise);
   126                                      Eigen::Vector3d::UnitZ() * 9.81,
   127                                      Eigen::Vector3d::Zero());
   132   std::vector<OptimizationProblem::Constraint> constraints;
   133   for (
int j = 0; j != kNumNodes; ++j) {
   135         mapping::SubmapId{0, 0}, mapping::NodeId{0, j},
   136         OptimizationProblem::Constraint::Pose{
   137             AddNoise(test_data[j].ground_truth_pose, test_data[j].noise), 1.,
   141         mapping::SubmapId{0, 1}, mapping::NodeId{0, j},
   142         OptimizationProblem::Constraint::Pose{
   143             AddNoise(test_data[j].ground_truth_pose,
   144                      RandomYawOnlyTransform(0.2, 0.3)),
   148         mapping::SubmapId{0, 2}, mapping::NodeId{0, j},
   149         OptimizationProblem::Constraint::Pose{
   150             kSubmap2Transform.inverse() * test_data[j].ground_truth_pose *
   151                 RandomTransform(1e3, 3.),
   155   double translation_error_before = 0.;
   156   double rotation_error_before = 0.;
   158   for (
int j = 0; j != kNumNodes; ++j) {
   159     translation_error_before += (test_data[j].ground_truth_pose.translation() -
   160                                  node_data[j].point_cloud_pose.translation())
   162     rotation_error_before +=
   164                             node_data[j].point_cloud_pose);
   172   double translation_error_after = 0.;
   173   double rotation_error_after = 0.;
   174   for (
int j = 0; j != kNumNodes; ++j) {
   175     translation_error_after += (test_data[j].ground_truth_pose.translation() -
   176                                 node_data[j].point_cloud_pose.translation())
   178     rotation_error_after +=
   180                             node_data[j].point_cloud_pose);
   183   EXPECT_GT(0.8 * translation_error_before, translation_error_after);
   184   EXPECT_GT(0.8 * rotation_error_before, rotation_error_after);
 
mapping::SparsePoseGraph::Constraint Constraint
UniversalTimeScaleClock::time_point Time
std::unique_ptr< LuaParameterDictionary > MakeDictionary(const string &code)
Time FromUniversal(const int64 ticks)
Duration FromSeconds(const double seconds)
proto::OptimizationProblemOptions CreateOptimizationProblemOptions(common::LuaParameterDictionary *const parameter_dictionary)
OptimizationProblem optimization_problem_