map_builder_test.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2017 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
19 #include "cartographer/common/config.h"
21 #include "gtest/gtest.h"
22 
23 namespace cartographer {
24 namespace mapping {
25 namespace {
26 
28 
29 const SensorId kRangeSensorId{SensorId::SensorType::RANGE, "range"};
30 const SensorId kIMUSensorId{SensorId::SensorType::IMU, "imu"};
31 constexpr double kDuration = 4.; // Seconds.
32 constexpr double kTimeStep = 0.1; // Seconds.
33 constexpr double kTravelDistance = 1.2; // Meters.
34 
35 class MapBuilderTest : public ::testing::Test {
36  protected:
37  void SetUp() override {
38  // Global SLAM optimization is not executed.
39  const std::string kMapBuilderLua = R"text(
40  include "map_builder.lua"
41  MAP_BUILDER.use_trajectory_builder_2d = true
42  MAP_BUILDER.pose_graph.optimize_every_n_nodes = 0
43  return MAP_BUILDER)text";
44  auto map_builder_parameters = test::ResolveLuaParameters(kMapBuilderLua);
46  CreateMapBuilderOptions(map_builder_parameters.get());
47  // Multiple submaps are created because of a small 'num_range_data'.
48  const std::string kTrajectoryBuilderLua = R"text(
49  include "trajectory_builder.lua"
50  TRAJECTORY_BUILDER.trajectory_builder_2d.use_imu_data = false
51  TRAJECTORY_BUILDER.trajectory_builder_2d.submaps.num_range_data = 4
52  TRAJECTORY_BUILDER.trajectory_builder_3d.submaps.num_range_data = 4
53  return TRAJECTORY_BUILDER)text";
54  auto trajectory_builder_parameters =
55  test::ResolveLuaParameters(kTrajectoryBuilderLua);
57  CreateTrajectoryBuilderOptions(trajectory_builder_parameters.get());
58  }
59 
60  void BuildMapBuilder() {
61  map_builder_ = common::make_unique<MapBuilder>(map_builder_options_);
62  }
63 
64  void SetOptionsTo3D() {
65  map_builder_options_.set_use_trajectory_builder_2d(false);
66  map_builder_options_.set_use_trajectory_builder_3d(true);
67  }
68 
69  void SetOptionsEnableGlobalOptimization() {
70  map_builder_options_.mutable_pose_graph_options()
71  ->set_optimize_every_n_nodes(3);
72  trajectory_builder_options_.mutable_trajectory_builder_2d_options()
73  ->mutable_motion_filter_options()
74  ->set_max_distance_meters(0);
75  }
76 
77  MapBuilderInterface::LocalSlamResultCallback GetLocalSlamResultCallback() {
78  return [=](const int trajectory_id, const ::cartographer::common::Time time,
80  ::cartographer::sensor::RangeData range_data_in_local,
81  const std::unique_ptr<
82  const cartographer::mapping::TrajectoryBuilderInterface::
83  InsertionResult>) {
84  local_slam_result_poses_.push_back(local_pose);
85  };
86  }
87 
88  std::unique_ptr<MapBuilderInterface> map_builder_;
89  proto::MapBuilderOptions map_builder_options_;
90  proto::TrajectoryBuilderOptions trajectory_builder_options_;
91  std::vector<::cartographer::transform::Rigid3d> local_slam_result_poses_;
92 };
93 
94 TEST_F(MapBuilderTest, TrajectoryAddFinish2D) {
95  BuildMapBuilder();
96  int trajectory_id = map_builder_->AddTrajectoryBuilder(
97  {kRangeSensorId}, trajectory_builder_options_,
98  nullptr /* GetLocalSlamResultCallbackForSubscriptions */);
99  EXPECT_EQ(1, map_builder_->num_trajectory_builders());
100  EXPECT_TRUE(map_builder_->GetTrajectoryBuilder(trajectory_id) != nullptr);
101  EXPECT_TRUE(map_builder_->pose_graph() != nullptr);
102  map_builder_->FinishTrajectory(trajectory_id);
103  map_builder_->pose_graph()->RunFinalOptimization();
104  EXPECT_TRUE(map_builder_->pose_graph()->IsTrajectoryFinished(trajectory_id));
105 }
106 
107 TEST_F(MapBuilderTest, TrajectoryAddFinish3D) {
108  SetOptionsTo3D();
109  BuildMapBuilder();
110  int trajectory_id = map_builder_->AddTrajectoryBuilder(
111  {kRangeSensorId}, trajectory_builder_options_,
112  nullptr /* GetLocalSlamResultCallbackForSubscriptions */);
113  EXPECT_EQ(1, map_builder_->num_trajectory_builders());
114  EXPECT_TRUE(map_builder_->GetTrajectoryBuilder(trajectory_id) != nullptr);
115  EXPECT_TRUE(map_builder_->pose_graph() != nullptr);
116  map_builder_->FinishTrajectory(trajectory_id);
117  map_builder_->pose_graph()->RunFinalOptimization();
118  EXPECT_TRUE(map_builder_->pose_graph()->IsTrajectoryFinished(trajectory_id));
119 }
120 
121 TEST_F(MapBuilderTest, LocalSlam2D) {
122  BuildMapBuilder();
123  int trajectory_id = map_builder_->AddTrajectoryBuilder(
124  {kRangeSensorId}, trajectory_builder_options_,
125  GetLocalSlamResultCallback());
126  TrajectoryBuilderInterface* trajectory_builder =
127  map_builder_->GetTrajectoryBuilder(trajectory_id);
128  const auto measurements = test::GenerateFakeRangeMeasurements(
129  kTravelDistance, kDuration, kTimeStep);
130  for (const auto& measurement : measurements) {
131  trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
132  }
133  map_builder_->FinishTrajectory(trajectory_id);
134  map_builder_->pose_graph()->RunFinalOptimization();
135  EXPECT_EQ(local_slam_result_poses_.size(), measurements.size());
136  EXPECT_NEAR(kTravelDistance,
137  (local_slam_result_poses_.back().translation() -
138  local_slam_result_poses_.front().translation())
139  .norm(),
140  0.1 * kTravelDistance);
141 }
142 
143 TEST_F(MapBuilderTest, LocalSlam3D) {
144  SetOptionsTo3D();
145  BuildMapBuilder();
146  int trajectory_id = map_builder_->AddTrajectoryBuilder(
147  {kRangeSensorId, kIMUSensorId}, trajectory_builder_options_,
148  GetLocalSlamResultCallback());
149  TrajectoryBuilderInterface* trajectory_builder =
150  map_builder_->GetTrajectoryBuilder(trajectory_id);
151  const auto measurements = test::GenerateFakeRangeMeasurements(
152  kTravelDistance, kDuration, kTimeStep);
153  for (const auto& measurement : measurements) {
154  trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
155  trajectory_builder->AddSensorData(
156  kIMUSensorId.id,
157  sensor::ImuData{measurement.time, Eigen::Vector3d(0., 0., 9.8),
158  Eigen::Vector3d::Zero()});
159  }
160  map_builder_->FinishTrajectory(trajectory_id);
161  map_builder_->pose_graph()->RunFinalOptimization();
162  EXPECT_EQ(local_slam_result_poses_.size(), measurements.size());
163  EXPECT_NEAR(kTravelDistance,
164  (local_slam_result_poses_.back().translation() -
165  local_slam_result_poses_.front().translation())
166  .norm(),
167  0.1 * kTravelDistance);
168 }
169 
170 TEST_F(MapBuilderTest, GlobalSlam2D) {
171  SetOptionsEnableGlobalOptimization();
172  BuildMapBuilder();
173  int trajectory_id = map_builder_->AddTrajectoryBuilder(
174  {kRangeSensorId}, trajectory_builder_options_,
175  GetLocalSlamResultCallback());
176  TrajectoryBuilderInterface* trajectory_builder =
177  map_builder_->GetTrajectoryBuilder(trajectory_id);
178  const auto measurements = test::GenerateFakeRangeMeasurements(
179  kTravelDistance, kDuration, kTimeStep);
180  for (const auto& measurement : measurements) {
181  trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
182  }
183  map_builder_->FinishTrajectory(trajectory_id);
184  map_builder_->pose_graph()->RunFinalOptimization();
185  EXPECT_EQ(local_slam_result_poses_.size(), measurements.size());
186  EXPECT_NEAR(kTravelDistance,
187  (local_slam_result_poses_.back().translation() -
188  local_slam_result_poses_.front().translation())
189  .norm(),
190  0.1 * kTravelDistance);
191  EXPECT_GE(map_builder_->pose_graph()->constraints().size(), 50);
192  const auto trajectory_nodes =
193  map_builder_->pose_graph()->GetTrajectoryNodes();
194  EXPECT_GE(trajectory_nodes.SizeOfTrajectoryOrZero(trajectory_id), 20);
195  const auto submap_data = map_builder_->pose_graph()->GetAllSubmapData();
196  EXPECT_GE(submap_data.SizeOfTrajectoryOrZero(trajectory_id), 5);
197  const transform::Rigid3d final_pose =
198  map_builder_->pose_graph()->GetLocalToGlobalTransform(trajectory_id) *
200  EXPECT_NEAR(kTravelDistance, final_pose.translation().norm(),
201  0.1 * kTravelDistance);
202 }
203 
204 TEST_F(MapBuilderTest, GlobalSlam3D) {
205  SetOptionsTo3D();
206  SetOptionsEnableGlobalOptimization();
207  BuildMapBuilder();
208  int trajectory_id = map_builder_->AddTrajectoryBuilder(
209  {kRangeSensorId, kIMUSensorId}, trajectory_builder_options_,
210  GetLocalSlamResultCallback());
211  TrajectoryBuilderInterface* trajectory_builder =
212  map_builder_->GetTrajectoryBuilder(trajectory_id);
213  const auto measurements = test::GenerateFakeRangeMeasurements(
214  kTravelDistance, kDuration, kTimeStep);
215  for (const auto& measurement : measurements) {
216  trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
217  trajectory_builder->AddSensorData(
218  kIMUSensorId.id,
219  sensor::ImuData{measurement.time, Eigen::Vector3d(0., 0., 9.8),
220  Eigen::Vector3d::Zero()});
221  }
222  map_builder_->FinishTrajectory(trajectory_id);
223  map_builder_->pose_graph()->RunFinalOptimization();
224  EXPECT_EQ(local_slam_result_poses_.size(), measurements.size());
225  EXPECT_NEAR(kTravelDistance,
226  (local_slam_result_poses_.back().translation() -
227  local_slam_result_poses_.front().translation())
228  .norm(),
229  0.1 * kTravelDistance);
230  EXPECT_GE(map_builder_->pose_graph()->constraints().size(), 10);
231  const auto trajectory_nodes =
232  map_builder_->pose_graph()->GetTrajectoryNodes();
233  EXPECT_GE(trajectory_nodes.SizeOfTrajectoryOrZero(trajectory_id), 5);
234  const auto submap_data = map_builder_->pose_graph()->GetAllSubmapData();
235  EXPECT_GE(submap_data.SizeOfTrajectoryOrZero(trajectory_id), 2);
236  const transform::Rigid3d final_pose =
237  map_builder_->pose_graph()->GetLocalToGlobalTransform(trajectory_id) *
239  EXPECT_NEAR(kTravelDistance, final_pose.translation().norm(),
240  0.1 * kTravelDistance);
241 }
242 
243 } // namespace
244 } // namespace mapping
245 } // namespace cartographer
TrajectoryBuilderInterface::LocalSlamResultCallback LocalSlamResultCallback
Rigid3< double > Rigid3d
std::vector< cartographer::sensor::TimedPointCloudData > GenerateFakeRangeMeasurements(double travel_distance, double duration, double time_step)
std::unique_ptr< MapBuilderInterface > map_builder_
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
proto::MapBuilderOptions CreateMapBuilderOptions(common::LuaParameterDictionary *const parameter_dictionary)
Definition: map_builder.cc:57
static time_point time
proto::TrajectoryBuilderOptions CreateTrajectoryBuilderOptions(common::LuaParameterDictionary *const parameter_dictionary)
std::vector<::cartographer::transform::Rigid3d > local_slam_result_poses_
proto::TrajectoryBuilderOptions trajectory_builder_options_
proto::MapBuilderOptions map_builder_options_
std::unique_ptr<::cartographer::common::LuaParameterDictionary > ResolveLuaParameters(const std::string &lua_code)
::cartographer::mapping::TrajectoryBuilderInterface::SensorId SensorId


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58