camera_pose_calibration_impl.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 Delft Robotics B.V.
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #pragma once
00018 
00019 #include <opencv2/opencv.hpp>
00020 
00021 #include <pcl/point_cloud.h>
00022 #include <pcl/point_types.h>
00023 #include <pcl/ModelCoefficients.h>
00024 
00025 #include <Eigen/Dense>
00026 #include <Eigen/Geometry>
00027 
00028 #include <boost/optional.hpp>
00029 
00030 namespace camera_pose_calibration {
00031 
00033 pcl::ModelCoefficients::Ptr fitPointsToPlane(
00034         pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloud   
00035 );
00036 
00038 std::vector<size_t> findNan(
00039         pcl::PointCloud<pcl::PointXYZ> const & cloud     
00040 );
00041 
00043 pcl::PointCloud<pcl::PointXYZ>::Ptr generateAsymmetricCircles(
00044         double distance,                            
00045         size_t pattern_height,                      
00046         size_t pattern_width                        
00047 );
00048 
00050 void projectCloudOnPlane(
00051         pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloud,       
00052         pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_projected,  
00053         pcl::ModelCoefficients::ConstPtr plane_coefficients   
00054 );
00055 
00057 void eraseIndices(
00058         std::vector<size_t> indices,                
00059         pcl::PointCloud<pcl::PointXYZ> & cloud      
00060 );
00061 
00063 Eigen::Isometry3d findIsometry(
00064         pcl::PointCloud<pcl::PointXYZ>::Ptr source, 
00065         pcl::PointCloud<pcl::PointXYZ>::Ptr target  
00066 );
00067 
00068 }


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