32 #include "gmock/gmock.h" 35 namespace mapping_2d {
38 class SparsePoseGraphTest :
public ::testing::Test {
45 for (
float t = 0.f; t < 2.f * M_PI; t += 0.005f) {
46 const float r = (std::sin(20.f * t) + 2.f) * std::sin(t + 2.f);
47 point_cloud_.emplace_back(r * std::sin(t), r * std::cos(t), 0.f);
56 output_debug_images = false, 57 range_data_inserter = { 58 insert_free_space = true, 59 hit_probability = 0.53, 60 miss_probability = 0.495, 63 submaps_ = common::make_unique<Submaps>( 70 optimize_every_n_scans = 1000, 71 constraint_builder = { 73 max_constraint_distance = 6., 74 adaptive_voxel_filter = { 76 min_num_points = 1000, 80 global_localization_min_score = 0.6, 81 loop_closure_translation_weight = 1., 82 loop_closure_rotation_weight = 1., 84 fast_correlative_scan_matcher = { 85 linear_search_window = 3., 86 angular_search_window = 0.1, 87 branch_and_bound_depth = 3, 89 ceres_scan_matcher = { 90 occupied_space_weight = 20., 91 translation_weight = 10., 93 ceres_solver_options = { 94 use_nonmonotonic_steps = true, 95 max_num_iterations = 50, 99 fast_correlative_scan_matcher_3d = { 100 branch_and_bound_depth = 3, 101 full_resolution_depth = 3, 102 rotational_histogram_size = 30, 103 min_rotational_score = 0.1, 104 linear_xy_search_window = 4., 105 linear_z_search_window = 4., 106 angular_search_window = 0.1, 108 ceres_scan_matcher_3d = { 109 occupied_space_weight_0 = 20., 110 translation_weight = 10., 111 rotation_weight = 1., 112 only_optimize_yaw = true, 113 ceres_solver_options = { 114 use_nonmonotonic_steps = true, 115 max_num_iterations = 50, 120 matcher_translation_weight = 1., 121 matcher_rotation_weight = 1., 122 optimization_problem = { 123 acceleration_weight = 1., 124 rotation_weight = 1e2, 126 consecutive_scan_translation_penalty_factor = 0., 127 consecutive_scan_rotation_penalty_factor = 0., 128 log_solver_summary = true, 129 ceres_solver_options = { 130 use_nonmonotonic_steps = false, 131 max_num_iterations = 200, 135 max_num_final_iterations = 200, 136 global_sampling_ratio = 0.01, 152 const mapping::Submap*
const matching_submap =
154 std::vector<const mapping::Submap*> insertion_submaps;
155 for (
int insertion_index :
submaps_->insertion_indices()) {
156 insertion_submaps.push_back(
submaps_->Get(insertion_index));
158 const sensor::RangeData range_data{
159 Eigen::Vector3f::Zero(), new_point_cloud, {}};
161 constexpr
int kTrajectoryId = 0;
166 pose_estimate, kTrajectoryId, matching_submap, insertion_submaps);
180 TEST_F(SparsePoseGraphTest, EmptyMap) {
183 EXPECT_THAT(nodes.size(), ::testing::Eq(0));
186 TEST_F(SparsePoseGraphTest, NoMovement) {
192 ASSERT_THAT(nodes.size(), ::testing::Eq(1));
193 EXPECT_THAT(nodes[0].size(), ::testing::Eq(3));
194 EXPECT_THAT(nodes[0][0].
pose,
196 EXPECT_THAT(nodes[0][1].pose,
198 EXPECT_THAT(nodes[0][2].pose,
202 TEST_F(SparsePoseGraphTest, NoOverlappingScans) {
204 std::uniform_real_distribution<double> distribution(-1., 1.);
205 std::vector<transform::Rigid2d> poses;
206 for (
int i = 0; i != 4; ++i) {
208 poses.emplace_back(current_pose_);
212 ASSERT_THAT(nodes.size(), ::testing::Eq(1));
213 for (
int i = 0; i != 4; ++i) {
214 EXPECT_THAT(poses[i],
220 TEST_F(SparsePoseGraphTest, ConsecutivelyOverlappingScans) {
222 std::uniform_real_distribution<double> distribution(-1., 1.);
223 std::vector<transform::Rigid2d> poses;
224 for (
int i = 0; i != 5; ++i) {
226 poses.emplace_back(current_pose_);
230 ASSERT_THAT(nodes.size(), ::testing::Eq(1));
231 for (
int i = 0; i != 5; ++i) {
232 EXPECT_THAT(poses[i],
238 TEST_F(SparsePoseGraphTest, OverlappingScans) {
240 std::uniform_real_distribution<double> distribution(-1., 1.);
241 std::vector<transform::Rigid2d> ground_truth;
242 std::vector<transform::Rigid2d> poses;
243 for (
int i = 0; i != 5; ++i) {
244 const double noise_x = 0.1 * distribution(rng);
245 const double noise_y = 0.1 * distribution(rng);
246 const double noise_orientation = 0.1 * distribution(rng);
248 MoveRelativeWithNoise(
250 ground_truth.emplace_back(current_pose_);
251 poses.emplace_back(noise * current_pose_);
255 ASSERT_THAT(nodes.size(), ::testing::Eq(1));
257 ground_truth.front().inverse() * ground_truth.back();
261 nodes[0].front().pose.
inverse() * nodes[0].back().pose;
264 EXPECT_THAT(std::abs(optimized_error.normalized_angle()),
265 ::testing::Lt(std::abs(error_before.normalized_angle())));
266 EXPECT_THAT(optimized_error.translation().norm(),
267 ::testing::Lt(error_before.translation().norm()));
PointCloud TransformPointCloud(const PointCloud &point_cloud, const transform::Rigid3f &transform)
common::ThreadPool thread_pool_
std::unique_ptr< SparsePoseGraph > sparse_pose_graph_
RangeData TransformRangeData(const RangeData &range_data, const transform::Rigid3f &transform)
std::unique_ptr< LuaParameterDictionary > MakeDictionary(const string &code)
Time FromUniversal(const int64 ticks)
proto::SubmapsOptions CreateSubmapsOptions(common::LuaParameterDictionary *const parameter_dictionary)
sensor::PointCloud point_cloud_
std::vector< Eigen::Vector3f > PointCloud
transform::Rigid2d current_pose_
std::unique_ptr< Submaps > submaps_
proto::SparsePoseGraphOptions CreateSparsePoseGraphOptions(common::LuaParameterDictionary *const parameter_dictionary)