occupied_space_cost_function_3d.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_INTERNAL_3D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTION_3D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_3D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTION_3D_H_
19 
20 #include "Eigen/Core"
26 
27 namespace cartographer {
28 namespace mapping {
29 namespace scan_matching {
30 
31 // Computes a cost for matching the 'point_cloud' to the 'hybrid_grid' with a
32 // 'translation' and 'rotation'. The cost increases when points fall into less
33 // occupied space, i.e. at voxels with lower values.
35  public:
36  static ceres::CostFunction* CreateAutoDiffCostFunction(
37  const double scaling_factor, const sensor::PointCloud& point_cloud,
38  const mapping::HybridGrid& hybrid_grid) {
39  return new ceres::AutoDiffCostFunction<
40  OccupiedSpaceCostFunction3D, ceres::DYNAMIC /* residuals */,
41  3 /* translation variables */, 4 /* rotation variables */>(
42  new OccupiedSpaceCostFunction3D(scaling_factor, point_cloud,
43  hybrid_grid),
44  point_cloud.size());
45  }
46 
47  template <typename T>
48  bool operator()(const T* const translation, const T* const rotation,
49  T* const residual) const {
50  const transform::Rigid3<T> transform(
51  Eigen::Map<const Eigen::Matrix<T, 3, 1>>(translation),
52  Eigen::Quaternion<T>(rotation[0], rotation[1], rotation[2],
53  rotation[3]));
54  return Evaluate(transform, residual);
55  }
56 
57  private:
58  OccupiedSpaceCostFunction3D(const double scaling_factor,
59  const sensor::PointCloud& point_cloud,
60  const mapping::HybridGrid& hybrid_grid)
61  : scaling_factor_(scaling_factor),
62  point_cloud_(point_cloud),
63  interpolated_grid_(hybrid_grid) {}
64 
67  delete;
68 
69  template <typename T>
70  bool Evaluate(const transform::Rigid3<T>& transform,
71  T* const residual) const {
72  for (size_t i = 0; i < point_cloud_.size(); ++i) {
73  const Eigen::Matrix<T, 3, 1> world =
74  transform * point_cloud_[i].cast<T>();
75  const T probability =
76  interpolated_grid_.GetProbability(world[0], world[1], world[2]);
77  residual[i] = scaling_factor_ * (1. - probability);
78  }
79  return true;
80  }
81 
82  const double scaling_factor_;
85 };
86 
87 } // namespace scan_matching
88 } // namespace mapping
89 } // namespace cartographer
90 
91 #endif // CARTOGRAPHER_MAPPING_INTERNAL_3D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTION_3D_H_
OccupiedSpaceCostFunction3D & operator=(const OccupiedSpaceCostFunction3D &)=delete
bool operator()(const T *const translation, const T *const rotation, T *const residual) const
OccupiedSpaceCostFunction3D(const double scaling_factor, const sensor::PointCloud &point_cloud, const mapping::HybridGrid &hybrid_grid)
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const sensor::PointCloud &point_cloud, const mapping::HybridGrid &hybrid_grid)
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:32
bool Evaluate(const transform::Rigid3< T > &transform, T *const residual) const
T GetProbability(const T &x, const T &y, const T &z) const


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58