Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_TESTING_TEST_HELPERS_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_TESTING_TEST_HELPERS_H_
00019
00020 #include <memory>
00021
00022 #include "cartographer/common/lua_parameter_dictionary.h"
00023 #include "cartographer/mapping/proto/serialization.pb.h"
00024 #include "cartographer/sensor/timed_point_cloud_data.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
00033 std::vector<cartographer::sensor::TimedPointCloudData>
00034 GenerateFakeRangeMeasurements(double travel_distance, double duration,
00035 double time_step);
00036
00037 std::vector<cartographer::sensor::TimedPointCloudData>
00038 GenerateFakeRangeMeasurements(const Eigen::Vector3f& translation,
00039 double duration, double time_step,
00040 const transform::Rigid3f& local_to_global);
00041
00042 proto::Submap CreateFakeSubmap3D(int trajectory_id = 1, int submap_index = 1,
00043 bool finished = true);
00044
00045 proto::Node CreateFakeNode(int trajectory_id = 1, int node_index = 1);
00046
00047 proto::PoseGraph::Constraint CreateFakeConstraint(const proto::Node& node,
00048 const proto::Submap& submap);
00049
00050 proto::Trajectory* CreateTrajectoryIfNeeded(int trajectory_id,
00051 proto::PoseGraph* pose_graph);
00052 proto::PoseGraph::LandmarkPose CreateFakeLandmark(
00053 const std::string& landmark_id, const transform::Rigid3d& global_pose);
00054
00055 void AddToProtoGraph(const proto::Node& node_data,
00056 proto::PoseGraph* pose_graph);
00057
00058 void AddToProtoGraph(const proto::Submap& submap_data,
00059 proto::PoseGraph* pose_graph);
00060
00061 void AddToProtoGraph(const proto::PoseGraph::Constraint& constraint,
00062 proto::PoseGraph* pose_graph);
00063
00064 void AddToProtoGraph(const proto::PoseGraph::LandmarkPose& landmark_node,
00065 proto::PoseGraph* pose_graph);
00066
00067 }
00068 }
00069 }
00070
00071 #endif // CARTOGRAPHER_MAPPING_INTERNAL_TESTING_TEST_HELPERS_H_