local_trajectory_builder_3d.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_3D_LOCAL_TRAJECTORY_BUILDER_3D_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_3D_LOCAL_TRAJECTORY_BUILDER_3D_H_
00019 
00020 #include <chrono>
00021 #include <memory>
00022 
00023 #include "cartographer/common/time.h"
00024 #include "cartographer/mapping/3d/submap_3d.h"
00025 #include "cartographer/mapping/internal/3d/scan_matching/ceres_scan_matcher_3d.h"
00026 #include "cartographer/mapping/internal/3d/scan_matching/real_time_correlative_scan_matcher_3d.h"
00027 #include "cartographer/mapping/internal/motion_filter.h"
00028 #include "cartographer/mapping/internal/range_data_collator.h"
00029 #include "cartographer/mapping/pose_extrapolator.h"
00030 #include "cartographer/mapping/proto/3d/local_trajectory_builder_options_3d.pb.h"
00031 #include "cartographer/metrics/family_factory.h"
00032 #include "cartographer/sensor/imu_data.h"
00033 #include "cartographer/sensor/internal/voxel_filter.h"
00034 #include "cartographer/sensor/odometry_data.h"
00035 #include "cartographer/sensor/range_data.h"
00036 #include "cartographer/transform/rigid_transform.h"
00037 
00038 namespace cartographer {
00039 namespace mapping {
00040 
00041 // Wires up the local SLAM stack (i.e. pose extrapolator, scan matching, etc.)
00042 // without loop closure.
00043 class LocalTrajectoryBuilder3D {
00044  public:
00045   struct InsertionResult {
00046     std::shared_ptr<const mapping::TrajectoryNode::Data> constant_data;
00047     std::vector<std::shared_ptr<const mapping::Submap3D>> insertion_submaps;
00048   };
00049   struct MatchingResult {
00050     common::Time time;
00051     transform::Rigid3d local_pose;
00052     sensor::RangeData range_data_in_local;
00053     // 'nullptr' if dropped by the motion filter.
00054     std::unique_ptr<const InsertionResult> insertion_result;
00055   };
00056 
00057   explicit LocalTrajectoryBuilder3D(
00058       const mapping::proto::LocalTrajectoryBuilderOptions3D& options,
00059       const std::vector<std::string>& expected_range_sensor_ids);
00060   ~LocalTrajectoryBuilder3D();
00061 
00062   LocalTrajectoryBuilder3D(const LocalTrajectoryBuilder3D&) = delete;
00063   LocalTrajectoryBuilder3D& operator=(const LocalTrajectoryBuilder3D&) = delete;
00064 
00065   void AddImuData(const sensor::ImuData& imu_data);
00066   // Returns 'MatchingResult' when range data accumulation completed,
00067   // otherwise 'nullptr'.  `TimedPointCloudData::time` is when the last point in
00068   // `range_data` was acquired, `TimedPointCloudData::ranges` contains the
00069   // relative time of point with respect to `TimedPointCloudData::time`.
00070   std::unique_ptr<MatchingResult> AddRangeData(
00071       const std::string& sensor_id,
00072       const sensor::TimedPointCloudData& range_data);
00073   void AddOdometryData(const sensor::OdometryData& odometry_data);
00074 
00075   static void RegisterMetrics(metrics::FamilyFactory* family_factory);
00076 
00077  private:
00078   std::unique_ptr<MatchingResult> AddAccumulatedRangeData(
00079       common::Time time,
00080       const sensor::RangeData& filtered_range_data_in_tracking,
00081       const absl::optional<common::Duration>& sensor_duration);
00082 
00083   std::unique_ptr<InsertionResult> InsertIntoSubmap(
00084       common::Time time, const sensor::RangeData& filtered_range_data_in_local,
00085       const sensor::RangeData& filtered_range_data_in_tracking,
00086       const sensor::PointCloud& high_resolution_point_cloud_in_tracking,
00087       const sensor::PointCloud& low_resolution_point_cloud_in_tracking,
00088       const transform::Rigid3d& pose_estimate,
00089       const Eigen::Quaterniond& gravity_alignment);
00090 
00091   // Scan matches using the two point clouds and returns the observed pose, or
00092   // nullptr on failure.
00093   std::unique_ptr<transform::Rigid3d> ScanMatch(
00094       const transform::Rigid3d& pose_prediction,
00095       const sensor::PointCloud& low_resolution_point_cloud_in_tracking,
00096       const sensor::PointCloud& high_resolution_point_cloud_in_tracking);
00097 
00098   const mapping::proto::LocalTrajectoryBuilderOptions3D options_;
00099   mapping::ActiveSubmaps3D active_submaps_;
00100 
00101   mapping::MotionFilter motion_filter_;
00102   std::unique_ptr<scan_matching::RealTimeCorrelativeScanMatcher3D>
00103       real_time_correlative_scan_matcher_;
00104   std::unique_ptr<scan_matching::CeresScanMatcher3D> ceres_scan_matcher_;
00105 
00106   std::unique_ptr<mapping::PoseExtrapolator> extrapolator_;
00107 
00108   int num_accumulated_ = 0;
00109   sensor::RangeData accumulated_range_data_;
00110   absl::optional<std::chrono::steady_clock::time_point> last_wall_time_;
00111 
00112   absl::optional<double> last_thread_cpu_time_seconds_;
00113 
00114   RangeDataCollator range_data_collator_;
00115 
00116   absl::optional<common::Time> last_sensor_time_;
00117 };
00118 
00119 }  // namespace mapping
00120 }  // namespace cartographer
00121 
00122 #endif  // CARTOGRAPHER_MAPPING_INTERNAL_3D_LOCAL_TRAJECTORY_BUILDER_3D_H_


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35