19 #include "cartographer/common/config.h" 21 #include "gtest/gtest.h" 31 constexpr
double kDuration = 4.;
32 constexpr
double kTimeStep = 0.1;
33 constexpr
double kTravelDistance = 1.2;
35 class MapBuilderTest :
public ::testing::Test {
37 void SetUp()
override {
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"; 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 =
60 void BuildMapBuilder() {
64 void SetOptionsTo3D() {
69 void SetOptionsEnableGlobalOptimization() {
71 ->set_optimize_every_n_nodes(3);
73 ->mutable_motion_filter_options()
74 ->set_max_distance_meters(0);
81 const std::unique_ptr<
82 const cartographer::mapping::TrajectoryBuilderInterface::
94 TEST_F(MapBuilderTest, TrajectoryAddFinish2D) {
100 EXPECT_TRUE(
map_builder_->GetTrajectoryBuilder(trajectory_id) !=
nullptr);
104 EXPECT_TRUE(
map_builder_->pose_graph()->IsTrajectoryFinished(trajectory_id));
107 TEST_F(MapBuilderTest, TrajectoryAddFinish3D) {
114 EXPECT_TRUE(
map_builder_->GetTrajectoryBuilder(trajectory_id) !=
nullptr);
118 EXPECT_TRUE(
map_builder_->pose_graph()->IsTrajectoryFinished(trajectory_id));
121 TEST_F(MapBuilderTest, LocalSlam2D) {
125 GetLocalSlamResultCallback());
126 TrajectoryBuilderInterface* trajectory_builder =
129 kTravelDistance, kDuration, kTimeStep);
130 for (
const auto& measurement : measurements) {
131 trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
136 EXPECT_NEAR(kTravelDistance,
140 0.1 * kTravelDistance);
143 TEST_F(MapBuilderTest, LocalSlam3D) {
148 GetLocalSlamResultCallback());
149 TrajectoryBuilderInterface* trajectory_builder =
152 kTravelDistance, kDuration, kTimeStep);
153 for (
const auto& measurement : measurements) {
154 trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
155 trajectory_builder->AddSensorData(
157 sensor::ImuData{measurement.time, Eigen::Vector3d(0., 0., 9.8),
158 Eigen::Vector3d::Zero()});
163 EXPECT_NEAR(kTravelDistance,
167 0.1 * kTravelDistance);
170 TEST_F(MapBuilderTest, GlobalSlam2D) {
171 SetOptionsEnableGlobalOptimization();
175 GetLocalSlamResultCallback());
176 TrajectoryBuilderInterface* trajectory_builder =
179 kTravelDistance, kDuration, kTimeStep);
180 for (
const auto& measurement : measurements) {
181 trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
186 EXPECT_NEAR(kTravelDistance,
190 0.1 * kTravelDistance);
191 EXPECT_GE(
map_builder_->pose_graph()->constraints().size(), 50);
192 const auto trajectory_nodes =
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);
198 map_builder_->pose_graph()->GetLocalToGlobalTransform(trajectory_id) *
200 EXPECT_NEAR(kTravelDistance, final_pose.translation().norm(),
201 0.1 * kTravelDistance);
204 TEST_F(MapBuilderTest, GlobalSlam3D) {
206 SetOptionsEnableGlobalOptimization();
210 GetLocalSlamResultCallback());
211 TrajectoryBuilderInterface* trajectory_builder =
214 kTravelDistance, kDuration, kTimeStep);
215 for (
const auto& measurement : measurements) {
216 trajectory_builder->AddSensorData(kRangeSensorId.id, measurement);
217 trajectory_builder->AddSensorData(
219 sensor::ImuData{measurement.time, Eigen::Vector3d(0., 0., 9.8),
220 Eigen::Vector3d::Zero()});
225 EXPECT_NEAR(kTravelDistance,
229 0.1 * kTravelDistance);
230 EXPECT_GE(
map_builder_->pose_graph()->constraints().size(), 10);
231 const auto trajectory_nodes =
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);
237 map_builder_->pose_graph()->GetLocalToGlobalTransform(trajectory_id) *
239 EXPECT_NEAR(kTravelDistance, final_pose.translation().norm(),
240 0.1 * kTravelDistance);
TrajectoryBuilderInterface::LocalSlamResultCallback LocalSlamResultCallback
std::vector< cartographer::sensor::TimedPointCloudData > GenerateFakeRangeMeasurements(double travel_distance, double duration, double time_step)
std::unique_ptr< MapBuilderInterface > map_builder_
UniversalTimeScaleClock::time_point Time
proto::MapBuilderOptions CreateMapBuilderOptions(common::LuaParameterDictionary *const parameter_dictionary)
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