real_time_correlative_scan_matcher_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_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_3D_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_3D_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_3D_H_
00019 
00020 #include <vector>
00021 
00022 #include "Eigen/Core"
00023 #include "cartographer/mapping/3d/hybrid_grid.h"
00024 #include "cartographer/mapping/proto/scan_matching/real_time_correlative_scan_matcher_options.pb.h"
00025 #include "cartographer/sensor/point_cloud.h"
00026 
00027 namespace cartographer {
00028 namespace mapping {
00029 namespace scan_matching {
00030 
00031 // A voxel accurate scan matcher, exhaustively evaluating the scan matching
00032 // search space.
00033 class RealTimeCorrelativeScanMatcher3D {
00034  public:
00035   explicit RealTimeCorrelativeScanMatcher3D(
00036       const scan_matching::proto::RealTimeCorrelativeScanMatcherOptions&
00037           options);
00038 
00039   RealTimeCorrelativeScanMatcher3D(const RealTimeCorrelativeScanMatcher3D&) =
00040       delete;
00041   RealTimeCorrelativeScanMatcher3D& operator=(
00042       const RealTimeCorrelativeScanMatcher3D&) = delete;
00043 
00044   // Aligns 'point_cloud' within the 'hybrid_grid' given an
00045   // 'initial_pose_estimate' then updates 'pose_estimate' with the result and
00046   // returns the score.
00047   float Match(const transform::Rigid3d& initial_pose_estimate,
00048               const sensor::PointCloud& point_cloud,
00049               const HybridGrid& hybrid_grid,
00050               transform::Rigid3d* pose_estimate) const;
00051 
00052  private:
00053   std::vector<transform::Rigid3f> GenerateExhaustiveSearchTransforms(
00054       float resolution, const sensor::PointCloud& point_cloud) const;
00055   float ScoreCandidate(const HybridGrid& hybrid_grid,
00056                        const sensor::PointCloud& transformed_point_cloud,
00057                        const transform::Rigid3f& transform) const;
00058 
00059   const proto::RealTimeCorrelativeScanMatcherOptions options_;
00060 };
00061 
00062 }  // namespace scan_matching
00063 }  // namespace mapping
00064 }  // namespace cartographer
00065 
00066 #endif  // CARTOGRAPHER_MAPPING_INTERNAL_3D_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_3D_H_


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