32 #include "gmock/gmock.h" 38 class PoseGraph2DTest :
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);
55 grid_type = "PROBABILITY_GRID", 58 range_data_inserter = { 59 range_data_inserter_type = "PROBABILITY_GRID_INSERTER_2D", 60 probability_grid_range_data_inserter = { 61 insert_free_space = true, 62 hit_probability = 0.53, 63 miss_probability = 0.495, 74 optimize_every_n_nodes = 1000, 75 constraint_builder = { 77 max_constraint_distance = 6., 79 global_localization_min_score = 0.6, 80 loop_closure_translation_weight = 1., 81 loop_closure_rotation_weight = 1., 83 fast_correlative_scan_matcher = { 84 linear_search_window = 3., 85 angular_search_window = 0.1, 86 branch_and_bound_depth = 3, 88 ceres_scan_matcher = { 89 occupied_space_weight = 20., 90 translation_weight = 10., 92 ceres_solver_options = { 93 use_nonmonotonic_steps = true, 94 max_num_iterations = 50, 98 fast_correlative_scan_matcher_3d = { 99 branch_and_bound_depth = 3, 100 full_resolution_depth = 3, 101 min_rotational_score = 0.1, 102 min_low_resolution_score = 0.5, 103 linear_xy_search_window = 4., 104 linear_z_search_window = 4., 105 angular_search_window = 0.1, 107 ceres_scan_matcher_3d = { 108 occupied_space_weight_0 = 20., 109 translation_weight = 10., 110 rotation_weight = 1., 111 only_optimize_yaw = true, 112 ceres_solver_options = { 113 use_nonmonotonic_steps = true, 114 max_num_iterations = 50, 119 matcher_translation_weight = 1., 120 matcher_rotation_weight = 1., 121 optimization_problem = { 122 acceleration_weight = 1., 123 rotation_weight = 1e2, 125 local_slam_pose_translation_weight = 0., 126 local_slam_pose_rotation_weight = 0., 127 odometry_translation_weight = 0., 128 odometry_rotation_weight = 0., 129 fixed_frame_pose_translation_weight = 1e1, 130 fixed_frame_pose_rotation_weight = 1e2, 131 log_solver_summary = true, 132 ceres_solver_options = { 133 use_nonmonotonic_steps = false, 134 max_num_iterations = 200, 138 max_num_final_iterations = 200, 139 global_sampling_ratio = 0.01, 140 log_residual_histograms = true, 141 global_constraint_search_after_n_seconds = 10.0, 146 common::make_unique<optimization::OptimizationProblem2D>(
147 options.optimization_problem_options()),
160 std::vector<std::shared_ptr<const Submap2D>> insertion_submaps;
162 insertion_submaps.push_back(submap);
164 const sensor::RangeData range_data{
165 Eigen::Vector3f::Zero(), new_point_cloud, {}};
167 constexpr
int kTrajectoryId = 0;
172 std::make_shared<const TrajectoryNode::Data>(
174 Eigen::Quaterniond::Identity(),
180 kTrajectoryId, insertion_submaps);
187 template <
typename Range>
188 std::vector<int> ToVectorInt(
const Range& range) {
189 return std::vector<int>(range.begin(), range.end());
199 TEST_F(PoseGraph2DTest, EmptyMap) {
201 const auto nodes =
pose_graph_->GetTrajectoryNodes();
202 EXPECT_TRUE(nodes.empty());
205 TEST_F(PoseGraph2DTest, NoMovement) {
210 const auto nodes =
pose_graph_->GetTrajectoryNodes();
211 ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
212 ::testing::ContainerEq(std::vector<int>{0}));
213 EXPECT_THAT(nodes.SizeOfTrajectoryOrZero(0), ::testing::Eq(3u));
214 EXPECT_THAT(nodes.at(NodeId{0, 0}).global_pose,
216 EXPECT_THAT(nodes.at(NodeId{0, 1}).global_pose,
218 EXPECT_THAT(nodes.at(NodeId{0, 2}).global_pose,
222 TEST_F(PoseGraph2DTest, NoOverlappingNodes) {
224 std::uniform_real_distribution<double> distribution(-1., 1.);
225 std::vector<transform::Rigid2d> poses;
226 for (
int i = 0; i != 4; ++i) {
228 poses.emplace_back(current_pose_);
231 const auto nodes =
pose_graph_->GetTrajectoryNodes();
232 ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
233 ::testing::ContainerEq(std::vector<int>{0}));
234 for (
int i = 0; i != 4; ++i) {
243 TEST_F(PoseGraph2DTest, ConsecutivelyOverlappingNodes) {
245 std::uniform_real_distribution<double> distribution(-1., 1.);
246 std::vector<transform::Rigid2d> poses;
247 for (
int i = 0; i != 5; ++i) {
249 poses.emplace_back(current_pose_);
252 const auto nodes =
pose_graph_->GetTrajectoryNodes();
253 ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
254 ::testing::ContainerEq(std::vector<int>{0}));
255 for (
int i = 0; i != 5; ++i) {
264 TEST_F(PoseGraph2DTest, OverlappingNodes) {
266 std::uniform_real_distribution<double> distribution(-1., 1.);
267 std::vector<transform::Rigid2d> ground_truth;
268 std::vector<transform::Rigid2d> poses;
269 for (
int i = 0; i != 5; ++i) {
270 const double noise_x = 0.1 * distribution(rng);
271 const double noise_y = 0.1 * distribution(rng);
272 const double noise_orientation = 0.1 * distribution(rng);
274 MoveRelativeWithNoise(
276 ground_truth.emplace_back(current_pose_);
277 poses.emplace_back(noise * current_pose_);
280 const auto nodes =
pose_graph_->GetTrajectoryNodes();
281 ASSERT_THAT(ToVectorInt(nodes.trajectory_ids()),
282 ::testing::ContainerEq(std::vector<int>{0}));
284 ground_truth.front().inverse() * ground_truth.back();
288 nodes.BeginOfTrajectory(0)->data.global_pose.
inverse() *
289 std::prev(nodes.EndOfTrajectory(0))->data.global_pose;
292 EXPECT_THAT(std::abs(optimized_error.normalized_angle()),
293 ::testing::Lt(std::abs(error_before.normalized_angle())));
294 EXPECT_THAT(optimized_error.translation().norm(),
295 ::testing::Lt(error_before.translation().norm()));
PointCloud TransformPointCloud(const PointCloud &point_cloud, const transform::Rigid3f &transform)
transform::Rigid2d current_pose_
sensor::PointCloud point_cloud_
proto::SubmapsOptions2D CreateSubmapsOptions2D(common::LuaParameterDictionary *const parameter_dictionary)
std::unique_ptr< LuaParameterDictionary > MakeDictionary(const std::string &code)
std::unique_ptr< ActiveSubmaps2D > active_submaps_
RangeData TransformRangeData(const RangeData &range_data, const transform::Rigid3f &transform)
Time FromUniversal(const int64 ticks)
proto::PoseGraphOptions CreatePoseGraphOptions(common::LuaParameterDictionary *const parameter_dictionary)
std::vector< Eigen::Vector3f > PointCloud
std::unique_ptr< PoseGraph2D > pose_graph_
common::ThreadPool thread_pool_