43 #include <pcl/gpu/containers/device_array.h>
44 #include <pcl/gpu/kinfu_large_scale/pixel_rgb.h>
46 #include <Eigen/Geometry>
48 #include <pcl/gpu/kinfu_large_scale/tsdf_buffer.h>
64 using Ptr = shared_ptr<RayCaster>;
81 RayCaster(
int rows = 480,
int cols = 640,
float fx = 525.f,
float fy = 525.f,
float cx = -1,
float cy = -1);
85 setIntrinsics(
float fx = 525.f,
float fy = 525.f,
float cx = -1,
float cy = -1);
124 float fx_, fy_, cx_, cy_;
142 Eigen::Affine3f camera_pose_;
145 Eigen::Vector3f volume_size_;
153 template<
typename Po
intType>
Defines all the PCL implemented PointT point type structures.
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Defines functions, macros and traits for allocating and using memory.
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 and non-PCL macros used.
Class that performs raycasting for TSDF volume.
MapArr getNormalMap() const
Returns raycasterd normal map.
RayCaster(int rows=480, int cols=640, float fx=525.f, float fy=525.f, float cx=-1, float cy=-1)
Constructor.
void run(const TsdfVolume &volume, const Eigen::Affine3f &camera_pose, tsdf_buffer *buffer)
Runs raycasting algorithm from given camera pose.
void setIntrinsics(float fx=525.f, float fy=525.f, float cx=-1, float cy=-1)
Sets camera intrinsics.
void generateSceneView(View &view) const
Generates scene view using data raycasted by run method.
shared_ptr< const RayCaster > ConstPtr
void generateDepthImage(Depth &depth) const
Generates depth image using data raycasted by run method.
MapArr getVertexMap() const
Returns raycasterd vertex map.
const int cols
Image with height.
shared_ptr< RayCaster > Ptr
void generateSceneView(View &view, const Eigen::Vector3f &light_source_pose) const
Generates scene view using data raycasted by run method.
Structure to handle buffer addresses.