Class InformationMatrixCalculator

Class Documentation

class InformationMatrixCalculator

Public Types

using PointT = pcl::PointXYZI

Public Functions

inline InformationMatrixCalculator()
InformationMatrixCalculator(const rclcpp::Node::SharedPtr node)
~InformationMatrixCalculator()
template<typename ParamServer>
inline void load(ParamServer &params)
Parameters:

params

Eigen::MatrixXd calc_information_matrix(const pcl::PointCloud<PointT>::ConstPtr &cloud1, const pcl::PointCloud<PointT>::ConstPtr &cloud2, const Eigen::Isometry3d &relpose) const
Parameters:
  • cloud1

  • cloud2

  • relpose

Returns:

Information matrix

Public Static Functions

static double calc_fitness_score(const pcl::PointCloud<PointT>::ConstPtr &cloud1, const pcl::PointCloud<PointT>::ConstPtr &cloud2, const Eigen::Isometry3d &relpose, double max_range = std::numeric_limits<double>::max())
Parameters:
  • cloud1

  • cloud2

  • relpose

  • max_range

Returns: