26 #include "glog/logging.h" 27 #include "gmock/gmock.h" 31 namespace optimization {
34 class OptimizationProblem3DTest :
public ::testing::Test {
36 OptimizationProblem3DTest()
39 optimization::proto::OptimizationProblemOptions CreateOptions() {
42 acceleration_weight = 1e-4, 43 rotation_weight = 1e-2, 45 local_slam_pose_translation_weight = 1e-2, 46 local_slam_pose_rotation_weight = 1e-2, 47 odometry_translation_weight = 1e-2, 48 odometry_rotation_weight = 1e-2, 49 fixed_frame_pose_translation_weight = 1e1, 50 fixed_frame_pose_rotation_weight = 1e2, 51 log_solver_summary = true, 52 ceres_solver_options = { 53 use_nonmonotonic_steps = false, 54 max_num_iterations = 200, 59 parameter_dictionary.get());
63 double rotation_size) {
64 std::uniform_real_distribution<double> translation_distribution(
65 -translation_size, translation_size);
66 const double x = translation_distribution(
rng_);
67 const double y = translation_distribution(
rng_);
68 const double z = translation_distribution(
rng_);
69 std::uniform_real_distribution<double> rotation_distribution(-rotation_size,
71 const double rx = rotation_distribution(
rng_);
72 const double ry = rotation_distribution(
rng_);
73 const double rz = rotation_distribution(
rng_);
76 Eigen::Vector3d(rx, ry, rz)));
80 double rotation_size) {
81 std::uniform_real_distribution<double> translation_distribution(
82 -translation_size, translation_size);
83 const double x = translation_distribution(
rng_);
84 const double y = translation_distribution(
rng_);
85 const double z = translation_distribution(
rng_);
86 std::uniform_real_distribution<double> rotation_distribution(-rotation_size,
88 const double rz = rotation_distribution(
rng_);
91 Eigen::Vector3d(0., 0., rz)));
100 const Eigen::Quaterniond noisy_rotation(noise.rotation() *
101 transform.rotation());
106 TEST_F(OptimizationProblem3DTest, ReducesNoise) {
107 constexpr
int kNumNodes = 100;
110 Eigen::AngleAxisd(M_PI, Eigen::Vector3d::UnitZ()));
111 const int kTrajectoryId = 0;
117 std::vector<NoisyNode> test_data;
118 for (
int j = 0; j != kNumNodes; ++j) {
120 NoisyNode{RandomTransform(10., 3.), RandomYawOnlyTransform(0.2, 0.3)});
124 for (
const NoisyNode& node : test_data) {
126 AddNoise(node.ground_truth_pose, node.noise);
128 kTrajectoryId, sensor::ImuData{now, Eigen::Vector3d::UnitZ() * 9.81,
129 Eigen::Vector3d::Zero()});
131 NodeSpec3D{now,
pose, pose});
135 std::vector<OptimizationProblem3D::Constraint> constraints;
136 for (
int j = 0; j != kNumNodes; ++j) {
138 SubmapId{kTrajectoryId, 0}, NodeId{kTrajectoryId, j},
139 OptimizationProblem3D::Constraint::Pose{
140 AddNoise(test_data[j].ground_truth_pose, test_data[j].noise), 1.,
144 SubmapId{kTrajectoryId, 1}, NodeId{kTrajectoryId, j},
145 OptimizationProblem3D::Constraint::Pose{
146 AddNoise(test_data[j].ground_truth_pose,
147 RandomYawOnlyTransform(0.2, 0.3)),
151 SubmapId{kTrajectoryId, 2}, NodeId{kTrajectoryId, j},
152 OptimizationProblem3D::Constraint::Pose{
153 kSubmap2Transform.inverse() * test_data[j].ground_truth_pose *
154 RandomTransform(1e3, 3.),
158 double translation_error_before = 0.;
159 double rotation_error_before = 0.;
161 for (
int j = 0; j != kNumNodes; ++j) {
162 translation_error_before +=
163 (test_data[j].ground_truth_pose.translation() -
164 node_data.at(NodeId{kTrajectoryId, j}).global_pose.translation())
166 rotation_error_before +=
168 node_data.at(NodeId{kTrajectoryId, j}).global_pose);
174 const std::set<int> kFrozen = {};
177 double translation_error_after = 0.;
178 double rotation_error_after = 0.;
179 for (
int j = 0; j != kNumNodes; ++j) {
180 translation_error_after +=
181 (test_data[j].ground_truth_pose.translation() -
182 node_data.at(NodeId{kTrajectoryId, j}).global_pose.translation())
184 rotation_error_after +=
186 node_data.at(NodeId{kTrajectoryId, j}).global_pose);
189 EXPECT_GT(0.8 * translation_error_before, translation_error_after);
190 EXPECT_GT(0.8 * rotation_error_before, rotation_error_after);
std::unique_ptr< LuaParameterDictionary > MakeDictionary(const std::string &code)
UniversalTimeScaleClock::time_point Time
proto::OptimizationProblemOptions CreateOptimizationProblemOptions(common::LuaParameterDictionary *const parameter_dictionary)
Time FromUniversal(const int64 ticks)
Duration FromSeconds(const double seconds)
OptimizationProblem3D optimization_problem_
PoseGraphInterface::Constraint Constraint