mapping/internal/testing/test_helpers.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"
25 
26 namespace cartographer {
27 namespace mapping {
28 namespace test {
29 
30 std::unique_ptr<::cartographer::common::LuaParameterDictionary>
31 ResolveLuaParameters(const std::string& lua_code) {
32  auto file_resolver = ::cartographer::common::make_unique<
34  std::vector<std::string>{
35  std::string(::cartographer::common::kSourceDirectory) +
36  "/configuration_files"});
37  return common::make_unique<::cartographer::common::LuaParameterDictionary>(
38  lua_code, std::move(file_resolver));
39 }
40 
41 std::vector<cartographer::sensor::TimedPointCloudData>
42 GenerateFakeRangeMeasurements(double travel_distance, double duration,
43  double time_step) {
44  std::vector<cartographer::sensor::TimedPointCloudData> measurements;
46  for (double angle = 0.; angle < M_PI; angle += 0.01) {
47  for (double height : {-0.4, -0.2, 0.0, 0.2, 0.4}) {
48  constexpr double kRadius = 5;
49  point_cloud.emplace_back(kRadius * std::cos(angle),
50  kRadius * std::sin(angle), height, 0.);
51  }
52  }
53  const Eigen::Vector3f kDirection = Eigen::Vector3f(2., 1., 0.).normalized();
54  const Eigen::Vector3f kVelocity = travel_distance / duration * kDirection;
55  for (double elapsed_time = 0.; elapsed_time < duration;
56  elapsed_time += time_step) {
61  cartographer::transform::Rigid3f::Translation(elapsed_time * kVelocity);
64  pose.inverse());
65  measurements.emplace_back(cartographer::sensor::TimedPointCloudData{
66  time, Eigen::Vector3f::Zero(), ranges});
67  }
68  return measurements;
69 }
70 
71 proto::Submap CreateFakeSubmap3D(int trajectory_id, int submap_index) {
72  proto::Submap proto;
73  proto.mutable_submap_id()->set_trajectory_id(trajectory_id);
74  proto.mutable_submap_id()->set_submap_index(submap_index);
75  proto.mutable_submap_3d()->set_num_range_data(1);
76  *proto.mutable_submap_3d()->mutable_local_pose() =
78  return proto;
79 }
80 
81 proto::Node CreateFakeNode(int trajectory_id, int node_index) {
82  proto::Node proto;
83  proto.mutable_node_id()->set_trajectory_id(trajectory_id);
84  proto.mutable_node_id()->set_node_index(node_index);
85  proto.mutable_node_data()->set_timestamp(42);
86  *proto.mutable_node_data()->mutable_local_pose() =
88  return proto;
89 }
90 
91 proto::PoseGraph::Constraint CreateFakeConstraint(const proto::Node& node,
92  const proto::Submap& submap) {
93  proto::PoseGraph::Constraint proto;
94  proto.mutable_submap_id()->set_submap_index(
95  submap.submap_id().submap_index());
96  proto.mutable_submap_id()->set_trajectory_id(
97  submap.submap_id().trajectory_id());
98  proto.mutable_node_id()->set_node_index(node.node_id().node_index());
99  proto.mutable_node_id()->set_trajectory_id(node.node_id().trajectory_id());
101  Eigen::Vector3d(2., 3., 4.),
102  Eigen::AngleAxisd(M_PI / 8., Eigen::Vector3d::UnitX()));
103  *proto.mutable_relative_pose() = transform::ToProto(pose);
104  proto.set_translation_weight(0.2f);
105  proto.set_rotation_weight(0.1f);
106  proto.set_tag(proto::PoseGraph::Constraint::INTER_SUBMAP);
107  return proto;
108 }
109 
110 proto::Trajectory* CreateTrajectoryIfNeeded(int trajectory_id,
111  proto::PoseGraph* pose_graph) {
112  for (int i = 0; i < pose_graph->trajectory_size(); ++i) {
113  proto::Trajectory* trajectory = pose_graph->mutable_trajectory(i);
114  if (trajectory->trajectory_id() == trajectory_id) {
115  return trajectory;
116  }
117  }
118  proto::Trajectory* trajectory = pose_graph->add_trajectory();
119  trajectory->set_trajectory_id(trajectory_id);
120  return trajectory;
121 }
122 
123 proto::PoseGraph::LandmarkPose CreateFakeLandmark(
124  const std::string& landmark_id, const transform::Rigid3d& global_pose) {
125  proto::PoseGraph::LandmarkPose landmark;
126  landmark.set_landmark_id(landmark_id);
127  *landmark.mutable_global_pose() = transform::ToProto(global_pose);
128  return landmark;
129 }
130 
131 void AddToProtoGraph(const proto::Node& node_data,
132  proto::PoseGraph* pose_graph) {
133  auto* trajectory =
134  CreateTrajectoryIfNeeded(node_data.node_id().trajectory_id(), pose_graph);
135  auto* node = trajectory->add_node();
136  node->set_timestamp(node_data.node_data().timestamp());
137  node->set_node_index(node_data.node_id().node_index());
138  *node->mutable_pose() = node_data.node_data().local_pose();
139 }
140 
141 void AddToProtoGraph(const proto::Submap& submap_data,
142  proto::PoseGraph* pose_graph) {
143  auto* trajectory = CreateTrajectoryIfNeeded(
144  submap_data.submap_id().trajectory_id(), pose_graph);
145  auto* submap = trajectory->add_submap();
146  submap->set_submap_index(submap_data.submap_id().submap_index());
147  if (submap_data.has_submap_2d()) {
148  *submap->mutable_pose() = submap_data.submap_2d().local_pose();
149  } else {
150  *submap->mutable_pose() = submap_data.submap_3d().local_pose();
151  }
152 }
153 
154 void AddToProtoGraph(const proto::PoseGraph::Constraint& constraint,
155  proto::PoseGraph* pose_graph) {
156  *pose_graph->add_constraint() = constraint;
157 }
158 
159 void AddToProtoGraph(const proto::PoseGraph::LandmarkPose& landmark,
160  proto::PoseGraph* pose_graph) {
161  *pose_graph->add_landmark_poses() = landmark;
162 }
163 
164 } // namespace test
165 } // namespace mapping
166 } // namespace cartographer
TimedPointCloud TransformTimedPointCloud(const TimedPointCloud &point_cloud, const transform::Rigid3f &transform)
Definition: point_cloud.cc:35
proto::PoseGraph::Constraint CreateFakeConstraint(const proto::Node &node, const proto::Submap &submap)
_Unique_if< T >::_Single_object make_unique(Args &&... args)
Definition: make_unique.h:46
void AddToProtoGraph(const proto::Node &node_data, proto::PoseGraph *pose_graph)
std::vector< cartographer::sensor::TimedPointCloudData > GenerateFakeRangeMeasurements(double travel_distance, double duration, double time_step)
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
Time FromUniversal(const int64 ticks)
Definition: time.cc:34
static time_point time
proto::Rigid2d ToProto(const transform::Rigid2d &transform)
Definition: transform.cc:48
Duration FromSeconds(const double seconds)
Definition: time.cc:24
proto::Submap CreateFakeSubmap3D(int trajectory_id, int submap_index)
std::vector< Eigen::Vector4f > TimedPointCloud
Definition: point_cloud.h:39
proto::PoseGraph::LandmarkPose CreateFakeLandmark(const std::string &landmark_id, const transform::Rigid3d &global_pose)
proto::Node CreateFakeNode(int trajectory_id, int node_index)
transform::Rigid3d pose
std::unique_ptr<::cartographer::common::LuaParameterDictionary > ResolveLuaParameters(const std::string &lua_code)
static Rigid3 Translation(const Vector &vector)
proto::Trajectory * CreateTrajectoryIfNeeded(int trajectory_id, proto::PoseGraph *pose_graph)


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