Namespaces | Functions
camera_pose_calibration_impl.hpp File Reference
#include <opencv2/opencv.hpp>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/ModelCoefficients.h>
#include <Eigen/Dense>
#include <Eigen/Geometry>
#include <boost/optional.hpp>
Include dependency graph for camera_pose_calibration_impl.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  camera_pose_calibration

Functions

void camera_pose_calibration::eraseIndices (std::vector< size_t > indices, pcl::PointCloud< pcl::PointXYZ > &cloud)
Eigen::Isometry3d camera_pose_calibration::findIsometry (pcl::PointCloud< pcl::PointXYZ >::Ptr source, pcl::PointCloud< pcl::PointXYZ >::Ptr target)
 Finds the isometry between two point clouds.
std::vector< size_t > camera_pose_calibration::findNan (pcl::PointCloud< pcl::PointXYZ > const &cloud)
 Returns the indices with nan value for x, y or z.
pcl::ModelCoefficients::Ptr camera_pose_calibration::fitPointsToPlane (pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud)
 Returns the plane parameters of the fit to the input point cloud.
pcl::PointCloud< pcl::PointXYZ >
::Ptr 
camera_pose_calibration::generateAsymmetricCircles (double distance, size_t pattern_height, size_t pattern_width)
 Defines the asymmetric circles calibration pattern.
void camera_pose_calibration::projectCloudOnPlane (pcl::PointCloud< pcl::PointXYZ >::ConstPtr cloud, pcl::PointCloud< pcl::PointXYZ >::Ptr cloud_projected, pcl::ModelCoefficients::ConstPtr plane_coefficients)
 Fits a plane to a point cloud and gives the projected point cloud and the plane coefficients.


camera_pose_calibration
Author(s): Hans Gaiser , Jeff van Egmond , Maarten de Vries , Mihai Morariu , Ronald Ensing
autogenerated on Thu Jun 6 2019 20:34:08