occupied_space_cost_function_2d.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_2D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTION_2D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTION_2D_H_
19 
20 #include "Eigen/Core"
21 #include "Eigen/Geometry"
25 #include "ceres/ceres.h"
26 #include "ceres/cubic_interpolation.h"
27 
28 namespace cartographer {
29 namespace mapping {
30 namespace scan_matching {
31 
32 // Computes a cost for matching the 'point_cloud' to the 'grid' with
33 // a 'pose'. The cost increases with poorer correspondence of the grid and the
34 // point observation (e.g. points falling into less occupied space).
36  public:
37  static ceres::CostFunction* CreateAutoDiffCostFunction(
38  const double scaling_factor, const sensor::PointCloud& point_cloud,
39  const Grid2D& grid) {
40  return new ceres::AutoDiffCostFunction<OccupiedSpaceCostFunction2D,
41  ceres::DYNAMIC /* residuals */,
42  3 /* pose variables */>(
43  new OccupiedSpaceCostFunction2D(scaling_factor, point_cloud, grid),
44  point_cloud.size());
45  }
46 
47  template <typename T>
48  bool operator()(const T* const pose, T* residual) const {
49  Eigen::Matrix<T, 2, 1> translation(pose[0], pose[1]);
50  Eigen::Rotation2D<T> rotation(pose[2]);
51  Eigen::Matrix<T, 2, 2> rotation_matrix = rotation.toRotationMatrix();
52  Eigen::Matrix<T, 3, 3> transform;
53  transform << rotation_matrix, translation, T(0.), T(0.), T(1.);
54 
55  const GridArrayAdapter adapter(grid_);
56  ceres::BiCubicInterpolator<GridArrayAdapter> interpolator(adapter);
57  const MapLimits& limits = grid_.limits();
58 
59  for (size_t i = 0; i < point_cloud_.size(); ++i) {
60  // Note that this is a 2D point. The third component is a scaling factor.
61  const Eigen::Matrix<T, 3, 1> point((T(point_cloud_[i].x())),
62  (T(point_cloud_[i].y())), T(1.));
63  const Eigen::Matrix<T, 3, 1> world = transform * point;
64  interpolator.Evaluate(
65  (limits.max().x() - world[0]) / limits.resolution() - 0.5 +
66  static_cast<double>(kPadding),
67  (limits.max().y() - world[1]) / limits.resolution() - 0.5 +
68  static_cast<double>(kPadding),
69  &residual[i]);
70  residual[i] = scaling_factor_ * residual[i];
71  }
72  return true;
73  }
74 
75  private:
76  static constexpr int kPadding = INT_MAX / 4;
78  public:
79  enum { DATA_DIMENSION = 1 };
80 
81  explicit GridArrayAdapter(const Grid2D& grid) : grid_(grid) {}
82 
83  void GetValue(const int row, const int column, double* const value) const {
84  if (row < kPadding || column < kPadding || row >= NumRows() - kPadding ||
85  column >= NumCols() - kPadding) {
86  *value = kMaxCorrespondenceCost;
87  } else {
88  *value = static_cast<double>(grid_.GetCorrespondenceCost(
89  Eigen::Array2i(column - kPadding, row - kPadding)));
90  }
91  }
92 
93  int NumRows() const {
94  return grid_.limits().cell_limits().num_y_cells + 2 * kPadding;
95  }
96 
97  int NumCols() const {
98  return grid_.limits().cell_limits().num_x_cells + 2 * kPadding;
99  }
100 
101  private:
102  const Grid2D& grid_;
103  };
104 
105  OccupiedSpaceCostFunction2D(const double scaling_factor,
106  const sensor::PointCloud& point_cloud,
107  const Grid2D& grid)
108  : scaling_factor_(scaling_factor),
109  point_cloud_(point_cloud),
110  grid_(grid) {}
111 
114  delete;
115 
116  const double scaling_factor_;
118  const Grid2D& grid_;
119 };
120 
121 } // namespace scan_matching
122 } // namespace mapping
123 } // namespace cartographer
124 
125 #endif // CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTION_2D_H_
const Eigen::Vector2d & max() const
Definition: map_limits.h:61
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const sensor::PointCloud &point_cloud, const Grid2D &grid)
constexpr float kMaxCorrespondenceCost
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:32
float GetCorrespondenceCost(const Eigen::Array2i &cell_index) const
Definition: grid_2d.cc:86
const MapLimits & limits() const
Definition: grid_2d.h:41
transform::Rigid3d pose
const CellLimits & cell_limits() const
Definition: map_limits.h:64
OccupiedSpaceCostFunction2D & operator=(const OccupiedSpaceCostFunction2D &)=delete
OccupiedSpaceCostFunction2D(const double scaling_factor, const sensor::PointCloud &point_cloud, const Grid2D &grid)


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