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_ 21 #include "Eigen/Geometry" 25 #include "ceres/ceres.h" 26 #include "ceres/cubic_interpolation.h" 30 namespace scan_matching {
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.);
56 ceres::BiCubicInterpolator<GridArrayAdapter> interpolator(adapter);
61 const Eigen::Matrix<T, 3, 1> point((T(
point_cloud_[i].x())),
63 const Eigen::Matrix<T, 3, 1> world = transform * point;
64 interpolator.Evaluate(
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) {
89 Eigen::Array2i(column - kPadding, row - kPadding)));
125 #endif // CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_OCCUPIED_SPACE_COST_FUNCTION_2D_H_ const Eigen::Vector2d & max() const
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const sensor::PointCloud &point_cloud, const Grid2D &grid)
bool operator()(const T *const pose, T *residual) const
const sensor::PointCloud & point_cloud_
const double scaling_factor_
double resolution() const
static constexpr int kPadding
constexpr float kMaxCorrespondenceCost
void GetValue(const int row, const int column, double *const value) const
GridArrayAdapter(const Grid2D &grid)
std::vector< Eigen::Vector3f > PointCloud
float GetCorrespondenceCost(const Eigen::Array2i &cell_index) const
const MapLimits & limits() const
const CellLimits & cell_limits() const
OccupiedSpaceCostFunction2D & operator=(const OccupiedSpaceCostFunction2D &)=delete
OccupiedSpaceCostFunction2D(const double scaling_factor, const sensor::PointCloud &point_cloud, const Grid2D &grid)