Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/mapping/internal/testing/test_helpers.h"
00018
00019 #include "absl/memory/memory.h"
00020 #include "cartographer/common/config.h"
00021 #include "cartographer/common/configuration_file_resolver.h"
00022 #include "cartographer/common/lua_parameter_dictionary_test_helpers.h"
00023 #include "cartographer/sensor/timed_point_cloud_data.h"
00024 #include "cartographer/transform/transform.h"
00025
00026 namespace cartographer {
00027 namespace mapping {
00028 namespace testing {
00029
00030 std::unique_ptr<::cartographer::common::LuaParameterDictionary>
00031 ResolveLuaParameters(const std::string& lua_code) {
00032 auto file_resolver =
00033 absl::make_unique<::cartographer::common::ConfigurationFileResolver>(
00034 std::vector<std::string>{
00035 std::string(::cartographer::common::kSourceDirectory) +
00036 "/configuration_files"});
00037 return absl::make_unique<::cartographer::common::LuaParameterDictionary>(
00038 lua_code, std::move(file_resolver));
00039 }
00040
00041 std::vector<cartographer::sensor::TimedPointCloudData>
00042 GenerateFakeRangeMeasurements(double travel_distance, double duration,
00043 double time_step) {
00044 const Eigen::Vector3f kDirection = Eigen::Vector3f(2., 1., 0.).normalized();
00045 return GenerateFakeRangeMeasurements(kDirection * travel_distance, duration,
00046 time_step,
00047 transform::Rigid3f::Identity());
00048 }
00049
00050 std::vector<cartographer::sensor::TimedPointCloudData>
00051 GenerateFakeRangeMeasurements(const Eigen::Vector3f& translation,
00052 double duration, double time_step,
00053 const transform::Rigid3f& local_to_global) {
00054 std::vector<cartographer::sensor::TimedPointCloudData> measurements;
00055 cartographer::sensor::TimedPointCloud point_cloud;
00056 for (double angle = 0.; angle < M_PI; angle += 0.01) {
00057 for (double height : {-0.4, -0.2, 0.0, 0.2, 0.4}) {
00058 constexpr double kRadius = 5;
00059 point_cloud.push_back({Eigen::Vector3d{kRadius * std::cos(angle),
00060 kRadius * std::sin(angle), height}
00061 .cast<float>(),
00062 0.});
00063 }
00064 }
00065 const Eigen::Vector3f kVelocity = translation / duration;
00066 for (double elapsed_time = 0.; elapsed_time < duration;
00067 elapsed_time += time_step) {
00068 cartographer::common::Time time =
00069 cartographer::common::FromUniversal(123) +
00070 cartographer::common::FromSeconds(elapsed_time);
00071 cartographer::transform::Rigid3f global_pose =
00072 local_to_global *
00073 cartographer::transform::Rigid3f::Translation(elapsed_time * kVelocity);
00074 cartographer::sensor::TimedPointCloud ranges =
00075 cartographer::sensor::TransformTimedPointCloud(point_cloud,
00076 global_pose.inverse());
00077 measurements.emplace_back(cartographer::sensor::TimedPointCloudData{
00078 time, Eigen::Vector3f::Zero(), ranges});
00079 }
00080 return measurements;
00081 }
00082
00083 proto::Submap CreateFakeSubmap3D(int trajectory_id, int submap_index,
00084 bool finished) {
00085 proto::Submap proto;
00086 proto.mutable_submap_id()->set_trajectory_id(trajectory_id);
00087 proto.mutable_submap_id()->set_submap_index(submap_index);
00088 proto.mutable_submap_3d()->set_num_range_data(1);
00089 *proto.mutable_submap_3d()->mutable_local_pose() =
00090 transform::ToProto(transform::Rigid3d::Identity());
00091 proto.mutable_submap_3d()->set_finished(finished);
00092 return proto;
00093 }
00094
00095 proto::Node CreateFakeNode(int trajectory_id, int node_index) {
00096 proto::Node proto;
00097 proto.mutable_node_id()->set_trajectory_id(trajectory_id);
00098 proto.mutable_node_id()->set_node_index(node_index);
00099 proto.mutable_node_data()->set_timestamp(42);
00100 *proto.mutable_node_data()->mutable_local_pose() =
00101 transform::ToProto(transform::Rigid3d::Identity());
00102 return proto;
00103 }
00104
00105 proto::PoseGraph::Constraint CreateFakeConstraint(const proto::Node& node,
00106 const proto::Submap& submap) {
00107 proto::PoseGraph::Constraint proto;
00108 proto.mutable_submap_id()->set_submap_index(
00109 submap.submap_id().submap_index());
00110 proto.mutable_submap_id()->set_trajectory_id(
00111 submap.submap_id().trajectory_id());
00112 proto.mutable_node_id()->set_node_index(node.node_id().node_index());
00113 proto.mutable_node_id()->set_trajectory_id(node.node_id().trajectory_id());
00114 transform::Rigid3d pose(
00115 Eigen::Vector3d(2., 3., 4.),
00116 Eigen::AngleAxisd(M_PI / 8., Eigen::Vector3d::UnitX()));
00117 *proto.mutable_relative_pose() = transform::ToProto(pose);
00118 proto.set_translation_weight(0.2f);
00119 proto.set_rotation_weight(0.1f);
00120 proto.set_tag(proto::PoseGraph::Constraint::INTER_SUBMAP);
00121 return proto;
00122 }
00123
00124 proto::Trajectory* CreateTrajectoryIfNeeded(int trajectory_id,
00125 proto::PoseGraph* pose_graph) {
00126 for (int i = 0; i < pose_graph->trajectory_size(); ++i) {
00127 proto::Trajectory* trajectory = pose_graph->mutable_trajectory(i);
00128 if (trajectory->trajectory_id() == trajectory_id) {
00129 return trajectory;
00130 }
00131 }
00132 proto::Trajectory* trajectory = pose_graph->add_trajectory();
00133 trajectory->set_trajectory_id(trajectory_id);
00134 return trajectory;
00135 }
00136
00137 proto::PoseGraph::LandmarkPose CreateFakeLandmark(
00138 const std::string& landmark_id, const transform::Rigid3d& global_pose) {
00139 proto::PoseGraph::LandmarkPose landmark;
00140 landmark.set_landmark_id(landmark_id);
00141 *landmark.mutable_global_pose() = transform::ToProto(global_pose);
00142 return landmark;
00143 }
00144
00145 void AddToProtoGraph(const proto::Node& node_data,
00146 proto::PoseGraph* pose_graph) {
00147 auto* trajectory =
00148 CreateTrajectoryIfNeeded(node_data.node_id().trajectory_id(), pose_graph);
00149 auto* node = trajectory->add_node();
00150 node->set_timestamp(node_data.node_data().timestamp());
00151 node->set_node_index(node_data.node_id().node_index());
00152 *node->mutable_pose() = node_data.node_data().local_pose();
00153 }
00154
00155 void AddToProtoGraph(const proto::Submap& submap_data,
00156 proto::PoseGraph* pose_graph) {
00157 auto* trajectory = CreateTrajectoryIfNeeded(
00158 submap_data.submap_id().trajectory_id(), pose_graph);
00159 auto* submap = trajectory->add_submap();
00160 submap->set_submap_index(submap_data.submap_id().submap_index());
00161 if (submap_data.has_submap_2d()) {
00162 *submap->mutable_pose() = submap_data.submap_2d().local_pose();
00163 } else {
00164 *submap->mutable_pose() = submap_data.submap_3d().local_pose();
00165 }
00166 }
00167
00168 void AddToProtoGraph(const proto::PoseGraph::Constraint& constraint,
00169 proto::PoseGraph* pose_graph) {
00170 *pose_graph->add_constraint() = constraint;
00171 }
00172
00173 void AddToProtoGraph(const proto::PoseGraph::LandmarkPose& landmark,
00174 proto::PoseGraph* pose_graph) {
00175 *pose_graph->add_landmark_poses() = landmark;
00176 }
00177
00178 }
00179 }
00180 }