39 #ifndef PCL_KINFU_TSDF_RAYCASTERLS_H_ 40 #define PCL_KINFU_TSDF_RAYCASTERLS_H_ 43 #include <pcl/pcl_macros.h> 45 #include <pcl/gpu/containers/device_array.h> 46 #include <pcl/gpu/kinfu_large_scale/pixel_rgb.h> 47 #include <boost/shared_ptr.hpp> 49 #include <Eigen/Geometry> 51 #include <pcl/gpu/kinfu_large_scale/tsdf_buffer.h> 67 typedef boost::shared_ptr<RayCaster>
Ptr;
83 RayCaster(
int rows = 480,
int cols = 640,
float fx = 525.f,
float fy = 525.f,
float cx = -1,
float cy = -1);
89 setIntrinsics(
float fx = 525.f,
float fy = 525.f,
float cx = -1,
float cy = -1);
103 generateSceneView(
View& view)
const;
110 generateSceneView(
View& view,
const Eigen::Vector3f& light_source_pose)
const;
116 generateDepthImage(
Depth& depth)
const;
120 getVertexMap()
const;
124 getNormalMap()
const;
128 float fx_, fy_, cx_, cy_;
146 Eigen::Affine3f camera_pose_;
149 Eigen::Vector3f volume_size_;
152 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
157 template<
typename Po
intType>
pcl::gpu::DeviceArray2D< PixelRGB > View
Structure to handle buffer addresses.
pcl::gpu::DeviceArray2D< float > MapArr
void convertMapToOranizedCloud(const RayCaster::MapArr &map, pcl::gpu::DeviceArray2D< PointType > &cloud)
Converts from map representation to organized not-dence point cloud.
Defines all the PCL implemented PointT point type structures.
pcl::gpu::DeviceArray2D< unsigned short > Depth
Class that performs raycasting for TSDF volume.
boost::shared_ptr< RayCaster > Ptr