mapping_3d/scan_matching/occupied_space_cost_functor.h
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef CARTOGRAPHER_MAPPING_3D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTOR_H_
18 #define CARTOGRAPHER_MAPPING_3D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTOR_H_
19 
20 #include "Eigen/Core"
26 
27 namespace cartographer {
28 namespace mapping_3d {
29 namespace scan_matching {
30 
31 // Computes the cost of inserting occupied space described by the point cloud
32 // into the map. The cost increases with the amount of free space that would be
33 // replaced by occupied space.
35  public:
36  // Creates an OccupiedSpaceCostFunctor using the specified grid, 'rotation' to
37  // add to all poses, and point cloud.
38  OccupiedSpaceCostFunctor(const double scaling_factor,
39  const sensor::PointCloud& point_cloud,
40  const HybridGrid& hybrid_grid)
41  : scaling_factor_(scaling_factor),
42  point_cloud_(point_cloud),
43  interpolated_grid_(hybrid_grid) {}
44 
47 
48  template <typename T>
49  bool operator()(const T* const translation, const T* const rotation,
50  T* const residual) const {
51  const transform::Rigid3<T> transform(
52  Eigen::Map<const Eigen::Matrix<T, 3, 1>>(translation),
53  Eigen::Quaternion<T>(rotation[0], rotation[1], rotation[2],
54  rotation[3]));
55  return Evaluate(transform, residual);
56  }
57 
58  template <typename T>
59  bool Evaluate(const transform::Rigid3<T>& transform,
60  T* const residual) const {
61  for (size_t i = 0; i < point_cloud_.size(); ++i) {
62  const Eigen::Matrix<T, 3, 1> world =
63  transform * point_cloud_[i].cast<T>();
64  const T probability =
65  interpolated_grid_.GetProbability(world[0], world[1], world[2]);
66  residual[i] = scaling_factor_ * (1. - probability);
67  }
68  return true;
69  }
70 
71  private:
72  const double scaling_factor_;
75 };
76 
77 } // namespace scan_matching
78 } // namespace mapping_3d
79 } // namespace cartographer
80 
81 #endif // CARTOGRAPHER_MAPPING_3D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTOR_H_
bool operator()(const T *const translation, const T *const rotation, T *const residual) const
bool Evaluate(const transform::Rigid3< T > &transform, T *const residual) const
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:30
OccupiedSpaceCostFunctor(const double scaling_factor, const sensor::PointCloud &point_cloud, const HybridGrid &hybrid_grid)
OccupiedSpaceCostFunctor & operator=(const OccupiedSpaceCostFunctor &)=delete
T GetProbability(const T &x, const T &y, const T &z) const


cartographer
Author(s):
autogenerated on Mon Jun 10 2019 12:51:39