Point Cloud Library (PCL)  1.14.0-dev
List of all members | Public Types | Public Member Functions | Public Attributes
pcl::gpu::RayCaster Struct Reference

Class that performs raycasting for TSDF volume. More...

#include </__w/1/s/gpu/kinfu/include/pcl/gpu/kinfu/raycaster.h>

Public Types

using Ptr = shared_ptr< RayCaster >
 
using ConstPtr = shared_ptr< const RayCaster >
 
using MapArr = DeviceArray2D< float >
 
using View = DeviceArray2D< PixelRGB >
 
using Depth = DeviceArray2D< unsigned short >
 

Public Member Functions

 RayCaster (int rows=480, int cols=640, float fx=525.f, float fy=525.f, float cx=-1, float cy=-1)
 Constructor. More...
 
void setIntrinsics (float fx=525.f, float fy=525.f, float cx=-1, float cy=-1)
 Sets camera intrinsics. More...
 
void run (const TsdfVolume &volume, const Eigen::Affine3f &camera_pose)
 Runs raycasting algorithm from given camera pose. More...
 
void generateSceneView (View &view) const
 Generates scene view using data raycasted by run method. More...
 
void generateSceneView (View &view, const Eigen::Vector3f &light_source_pose) const
 Generates scene view using data raycasted by run method. More...
 
void generateDepthImage (Depth &depth) const
 Generates depth image using data raycasted by run method. More...
 
MapArr getVertexMap () const
 Returns raycasterd vertex map. More...
 
MapArr getNormalMap () const
 Returns raycasterd normal map. More...
 

Public Attributes

const int cols
 Image with height. More...
 
const int rows
 

Detailed Description

Class that performs raycasting for TSDF volume.

Author
Anatoly Baskeheev, Itseez Ltd, (mynam.nosp@m.e.my.nosp@m.surna.nosp@m.me@m.nosp@m.ycomp.nosp@m.any..nosp@m.com)

Definition at line 56 of file raycaster.h.

Member Typedef Documentation

◆ ConstPtr

using pcl::gpu::RayCaster::ConstPtr = shared_ptr<const RayCaster>

Definition at line 60 of file raycaster.h.

◆ Depth

using pcl::gpu::RayCaster::Depth = DeviceArray2D<unsigned short>

Definition at line 63 of file raycaster.h.

◆ MapArr

Definition at line 61 of file raycaster.h.

◆ Ptr

using pcl::gpu::RayCaster::Ptr = shared_ptr<RayCaster>

Definition at line 59 of file raycaster.h.

◆ View

Definition at line 62 of file raycaster.h.

Constructor & Destructor Documentation

◆ RayCaster()

pcl::gpu::RayCaster::RayCaster ( int  rows = 480,
int  cols = 640,
float  fx = 525.f,
float  fy = 525.f,
float  cx = -1,
float  cy = -1 
)

Constructor.

Parameters
[in]rowsimage rows
[in]colsimage cols
[in]fxfocal x
[in]fyfocal y
[in]cxprincipal point x
[in]cyprincipal point y

Member Function Documentation

◆ generateDepthImage()

void pcl::gpu::RayCaster::generateDepthImage ( Depth depth) const

Generates depth image using data raycasted by run method.

So call it before.

Parameters
[out]depthoutput array for depth image

◆ generateSceneView() [1/2]

void pcl::gpu::RayCaster::generateSceneView ( View view) const

Generates scene view using data raycasted by run method.

So call it before.

Parameters
[out]viewoutput array for RGB image

◆ generateSceneView() [2/2]

void pcl::gpu::RayCaster::generateSceneView ( View view,
const Eigen::Vector3f &  light_source_pose 
) const

Generates scene view using data raycasted by run method.

So call it before.

Parameters
[out]viewoutput array for RGB image
[in]light_source_posepose of light source

◆ getNormalMap()

MapArr pcl::gpu::RayCaster::getNormalMap ( ) const

Returns raycasterd normal map.

◆ getVertexMap()

MapArr pcl::gpu::RayCaster::getVertexMap ( ) const

Returns raycasterd vertex map.

◆ run()

void pcl::gpu::RayCaster::run ( const TsdfVolume volume,
const Eigen::Affine3f &  camera_pose 
)

Runs raycasting algorithm from given camera pose.

It writes results to internal files.

Parameters
[in]volumetsdf volume container
[in]camera_posecamera pose

◆ setIntrinsics()

void pcl::gpu::RayCaster::setIntrinsics ( float  fx = 525.f,
float  fy = 525.f,
float  cx = -1,
float  cy = -1 
)

Sets camera intrinsics.

Member Data Documentation

◆ cols

const int pcl::gpu::RayCaster::cols

Image with height.

Definition at line 66 of file raycaster.h.

◆ rows

const int pcl::gpu::RayCaster::rows

Definition at line 66 of file raycaster.h.


The documentation for this struct was generated from the following file: