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_ 29 namespace scan_matching {
39 return new ceres::AutoDiffCostFunction<
48 bool operator()(
const T*
const translation,
const T*
const rotation,
49 T*
const residual)
const {
51 Eigen::Map<
const Eigen::Matrix<T, 3, 1>>(translation),
52 Eigen::Quaternion<T>(rotation[0], rotation[1], rotation[2],
54 return Evaluate(transform, residual);
71 T*
const residual)
const {
73 const Eigen::Matrix<T, 3, 1> world =
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)
const InterpolatedGrid interpolated_grid_
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const sensor::PointCloud &point_cloud, const mapping::HybridGrid &hybrid_grid)
const double scaling_factor_
std::vector< Eigen::Vector3f > PointCloud
bool Evaluate(const transform::Rigid3< T > &transform, T *const residual) const
const sensor::PointCloud & point_cloud_
T GetProbability(const T &x, const T &y, const T &z) const