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 <random>
00020
00021 #include "Eigen/Core"
00022 #include "cartographer/common/lua_parameter_dictionary_test_helpers.h"
00023 #include "cartographer/common/time.h"
00024 #include "cartographer/mapping/internal/optimization/optimization_problem_options.h"
00025 #include "cartographer/transform/transform.h"
00026 #include "glog/logging.h"
00027 #include "gmock/gmock.h"
00028
00029 namespace cartographer {
00030 namespace mapping {
00031 namespace optimization {
00032 namespace {
00033
00034 class OptimizationProblem3DTest : public ::testing::Test {
00035 protected:
00036 OptimizationProblem3DTest()
00037 : optimization_problem_(CreateOptions()), rng_(45387) {}
00038
00039 optimization::proto::OptimizationProblemOptions CreateOptions() {
00040 auto parameter_dictionary = common::MakeDictionary(R"text(
00041 return {
00042 acceleration_weight = 1e-4,
00043 rotation_weight = 1e-2,
00044 huber_scale = 1.,
00045 local_slam_pose_translation_weight = 1e-2,
00046 local_slam_pose_rotation_weight = 1e-2,
00047 odometry_translation_weight = 1e-2,
00048 odometry_rotation_weight = 1e-2,
00049 fixed_frame_pose_translation_weight = 1e1,
00050 fixed_frame_pose_rotation_weight = 1e2,
00051 log_solver_summary = true,
00052 use_online_imu_extrinsics_in_3d = true,
00053 fix_z_in_3d = false,
00054 ceres_solver_options = {
00055 use_nonmonotonic_steps = false,
00056 max_num_iterations = 200,
00057 num_threads = 4,
00058 },
00059 })text");
00060 return optimization::CreateOptimizationProblemOptions(
00061 parameter_dictionary.get());
00062 }
00063
00064 transform::Rigid3d RandomTransform(double translation_size,
00065 double rotation_size) {
00066 std::uniform_real_distribution<double> translation_distribution(
00067 -translation_size, translation_size);
00068 const double x = translation_distribution(rng_);
00069 const double y = translation_distribution(rng_);
00070 const double z = translation_distribution(rng_);
00071 std::uniform_real_distribution<double> rotation_distribution(-rotation_size,
00072 rotation_size);
00073 const double rx = rotation_distribution(rng_);
00074 const double ry = rotation_distribution(rng_);
00075 const double rz = rotation_distribution(rng_);
00076 return transform::Rigid3d(Eigen::Vector3d(x, y, z),
00077 transform::AngleAxisVectorToRotationQuaternion(
00078 Eigen::Vector3d(rx, ry, rz)));
00079 }
00080
00081 transform::Rigid3d RandomYawOnlyTransform(double translation_size,
00082 double rotation_size) {
00083 std::uniform_real_distribution<double> translation_distribution(
00084 -translation_size, translation_size);
00085 const double x = translation_distribution(rng_);
00086 const double y = translation_distribution(rng_);
00087 const double z = translation_distribution(rng_);
00088 std::uniform_real_distribution<double> rotation_distribution(-rotation_size,
00089 rotation_size);
00090 const double rz = rotation_distribution(rng_);
00091 return transform::Rigid3d(Eigen::Vector3d(x, y, z),
00092 transform::AngleAxisVectorToRotationQuaternion(
00093 Eigen::Vector3d(0., 0., rz)));
00094 }
00095
00096 OptimizationProblem3D optimization_problem_;
00097 std::mt19937 rng_;
00098 };
00099
00100 transform::Rigid3d AddNoise(const transform::Rigid3d& transform,
00101 const transform::Rigid3d& noise) {
00102 const Eigen::Quaterniond noisy_rotation(noise.rotation() *
00103 transform.rotation());
00104 return transform::Rigid3d(transform.translation() + noise.translation(),
00105 noisy_rotation);
00106 }
00107
00108 TEST_F(OptimizationProblem3DTest, ReducesNoise) {
00109 constexpr int kNumNodes = 100;
00110 const transform::Rigid3d kSubmap0Transform = transform::Rigid3d::Identity();
00111 const transform::Rigid3d kSubmap2Transform = transform::Rigid3d::Rotation(
00112 Eigen::AngleAxisd(M_PI, Eigen::Vector3d::UnitZ()));
00113 const int kTrajectoryId = 0;
00114
00115 struct NoisyNode {
00116 transform::Rigid3d ground_truth_pose;
00117 transform::Rigid3d noise;
00118 };
00119 std::vector<NoisyNode> test_data;
00120 for (int j = 0; j != kNumNodes; ++j) {
00121 test_data.push_back(
00122 NoisyNode{RandomTransform(10., 3.), RandomYawOnlyTransform(0.2, 0.3)});
00123 }
00124
00125 common::Time now = common::FromUniversal(0);
00126 for (const NoisyNode& node : test_data) {
00127 const transform::Rigid3d pose =
00128 AddNoise(node.ground_truth_pose, node.noise);
00129 optimization_problem_.AddImuData(
00130 kTrajectoryId, sensor::ImuData{now, Eigen::Vector3d::UnitZ() * 9.81,
00131 Eigen::Vector3d::Zero()});
00132 optimization_problem_.AddTrajectoryNode(kTrajectoryId,
00133 NodeSpec3D{now, pose, pose});
00134 now += common::FromSeconds(0.01);
00135 }
00136
00137 std::vector<OptimizationProblem3D::Constraint> constraints;
00138 for (int j = 0; j != kNumNodes; ++j) {
00139 constraints.push_back(OptimizationProblem3D::Constraint{
00140 SubmapId{kTrajectoryId, 0}, NodeId{kTrajectoryId, j},
00141 OptimizationProblem3D::Constraint::Pose{
00142 AddNoise(test_data[j].ground_truth_pose, test_data[j].noise), 1.,
00143 1.}});
00144
00145 constraints.push_back(OptimizationProblem3D::Constraint{
00146 SubmapId{kTrajectoryId, 1}, NodeId{kTrajectoryId, j},
00147 OptimizationProblem3D::Constraint::Pose{
00148 AddNoise(test_data[j].ground_truth_pose,
00149 RandomYawOnlyTransform(0.2, 0.3)),
00150 1., 1.}});
00151
00152 constraints.push_back(OptimizationProblem3D::Constraint{
00153 SubmapId{kTrajectoryId, 2}, NodeId{kTrajectoryId, j},
00154 OptimizationProblem3D::Constraint::Pose{
00155 kSubmap2Transform.inverse() * test_data[j].ground_truth_pose *
00156 RandomTransform(1e3, 3.),
00157 1e-9, 1e-9}});
00158 }
00159
00160 double translation_error_before = 0.;
00161 double rotation_error_before = 0.;
00162 const auto& node_data = optimization_problem_.node_data();
00163 for (int j = 0; j != kNumNodes; ++j) {
00164 translation_error_before +=
00165 (test_data[j].ground_truth_pose.translation() -
00166 node_data.at(NodeId{kTrajectoryId, j}).global_pose.translation())
00167 .norm();
00168 rotation_error_before +=
00169 transform::GetAngle(test_data[j].ground_truth_pose.inverse() *
00170 node_data.at(NodeId{kTrajectoryId, j}).global_pose);
00171 }
00172
00173 optimization_problem_.AddSubmap(kTrajectoryId, kSubmap0Transform);
00174 optimization_problem_.AddSubmap(kTrajectoryId, kSubmap0Transform);
00175 optimization_problem_.AddSubmap(kTrajectoryId, kSubmap2Transform);
00176 const std::map<int, PoseGraphInterface::TrajectoryState> kTrajectoriesState =
00177 {{kTrajectoryId, PoseGraphInterface::TrajectoryState::ACTIVE}};
00178 optimization_problem_.Solve(constraints, kTrajectoriesState, {});
00179
00180 double translation_error_after = 0.;
00181 double rotation_error_after = 0.;
00182 for (int j = 0; j != kNumNodes; ++j) {
00183 translation_error_after +=
00184 (test_data[j].ground_truth_pose.translation() -
00185 node_data.at(NodeId{kTrajectoryId, j}).global_pose.translation())
00186 .norm();
00187 rotation_error_after +=
00188 transform::GetAngle(test_data[j].ground_truth_pose.inverse() *
00189 node_data.at(NodeId{kTrajectoryId, j}).global_pose);
00190 }
00191
00192 EXPECT_GT(0.8 * translation_error_before, translation_error_after);
00193 EXPECT_GT(0.8 * rotation_error_before, rotation_error_after);
00194 }
00195
00196 }
00197 }
00198 }
00199 }