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_COLLATED_TRAJECTORY_BUILDER_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_COLLATED_TRAJECTORY_BUILDER_H_
00019
00020 #include <chrono>
00021 #include <map>
00022 #include <memory>
00023 #include <set>
00024 #include <string>
00025
00026 #include "cartographer/common/port.h"
00027 #include "cartographer/common/rate_timer.h"
00028 #include "cartographer/mapping/local_slam_result_data.h"
00029 #include "cartographer/mapping/submaps.h"
00030 #include "cartographer/mapping/trajectory_builder_interface.h"
00031 #include "cartographer/sensor/collator_interface.h"
00032 #include "cartographer/sensor/internal/dispatchable.h"
00033
00034 namespace cartographer {
00035 namespace mapping {
00036
00037
00038
00039 class CollatedTrajectoryBuilder : public TrajectoryBuilderInterface {
00040 public:
00041 using SensorId = TrajectoryBuilderInterface::SensorId;
00042
00043 CollatedTrajectoryBuilder(
00044 const proto::TrajectoryBuilderOptions& trajectory_options,
00045 sensor::CollatorInterface* sensor_collator, int trajectory_id,
00046 const std::set<SensorId>& expected_sensor_ids,
00047 std::unique_ptr<TrajectoryBuilderInterface> wrapped_trajectory_builder);
00048 ~CollatedTrajectoryBuilder() override {}
00049
00050 CollatedTrajectoryBuilder(const CollatedTrajectoryBuilder&) = delete;
00051 CollatedTrajectoryBuilder& operator=(const CollatedTrajectoryBuilder&) =
00052 delete;
00053
00054 void AddSensorData(
00055 const std::string& sensor_id,
00056 const sensor::TimedPointCloudData& timed_point_cloud_data) override {
00057 AddData(sensor::MakeDispatchable(sensor_id, timed_point_cloud_data));
00058 }
00059
00060 void AddSensorData(const std::string& sensor_id,
00061 const sensor::ImuData& imu_data) override {
00062 AddData(sensor::MakeDispatchable(sensor_id, imu_data));
00063 }
00064
00065 void AddSensorData(const std::string& sensor_id,
00066 const sensor::OdometryData& odometry_data) override {
00067 AddData(sensor::MakeDispatchable(sensor_id, odometry_data));
00068 }
00069
00070 void AddSensorData(
00071 const std::string& sensor_id,
00072 const sensor::FixedFramePoseData& fixed_frame_pose_data) override {
00073 if (collate_fixed_frame_) {
00074 AddData(sensor::MakeDispatchable(sensor_id, fixed_frame_pose_data));
00075 return;
00076 }
00077 wrapped_trajectory_builder_->AddSensorData(sensor_id,
00078 fixed_frame_pose_data);
00079 }
00080
00081 void AddSensorData(const std::string& sensor_id,
00082 const sensor::LandmarkData& landmark_data) override {
00083 if (collate_landmarks_) {
00084 AddData(sensor::MakeDispatchable(sensor_id, landmark_data));
00085 return;
00086 }
00087 wrapped_trajectory_builder_->AddSensorData(sensor_id, landmark_data);
00088 }
00089
00090 void AddLocalSlamResultData(std::unique_ptr<mapping::LocalSlamResultData>
00091 local_slam_result_data) override {
00092 AddData(std::move(local_slam_result_data));
00093 }
00094
00095 private:
00096 void AddData(std::unique_ptr<sensor::Data> data);
00097
00098 void HandleCollatedSensorData(const std::string& sensor_id,
00099 std::unique_ptr<sensor::Data> data);
00100
00101 sensor::CollatorInterface* const sensor_collator_;
00102 const bool collate_landmarks_;
00103 const bool collate_fixed_frame_;
00104 const int trajectory_id_;
00105 std::unique_ptr<TrajectoryBuilderInterface> wrapped_trajectory_builder_;
00106
00107
00108 std::chrono::steady_clock::time_point last_logging_time_;
00109 std::map<std::string, common::RateTimer<>> rate_timers_;
00110 };
00111
00112 }
00113 }
00114
00115 #endif // CARTOGRAPHER_MAPPING_INTERNAL_COLLATED_TRAJECTORY_BUILDER_H_