Go to the source code of this file.
|
std::unique_ptr< ensenso::pcl::PointCloud > | pointCloudFromNxLib (NxLibItem const &node, std::string const &frame, bool isFileCamera=false, PointCloudROI const *roi=nullptr) |
|
std::unique_ptr< ensenso::pcl::PointCloudColored > | pointCloudTexturedFromNxLib (NxLibItem const &imageNode, NxLibItem const &pointsNode, std::string const &frame, bool isFileCamera=false, PointCloudROI const *roi=nullptr) |
|
std::unique_ptr< ensenso::pcl::PointCloudNormals > | pointCloudWithNormalsFromNxLib (NxLibItem const &pointMapNode, NxLibItem const &normalNode, std::string const &frame, bool isFileCamera=false, PointCloudROI const *roi=nullptr) |
|
sensor_msgs::msg::ImagePtr | retrieveRenderedDepthMap (NxLibItem const &cmdResult, std::string const &frame, bool isFileCamera) |
|
std::unique_ptr< ensenso::pcl::PointCloud > | retrieveRenderedPointCloud (NxLibItem const &cmdResult, std::string const &frame, bool isFileCamera=false) |
|
std::unique_ptr< ensenso::pcl::PointCloudColored > | retrieveTexturedPointCloud (NxLibItem const &cmdResult, std::string const &targetFrame, bool isFileCamera=false) |
|
void | setRenderParams (NxLibItem const &cmdParams, RenderPointMapParams const *params) |
|
◆ pointCloudFromNxLib()
◆ pointCloudTexturedFromNxLib()
std::unique_ptr<ensenso::pcl::PointCloudColored> pointCloudTexturedFromNxLib |
( |
NxLibItem const & |
imageNode, |
|
|
NxLibItem const & |
pointsNode, |
|
|
std::string const & |
frame, |
|
|
bool |
isFileCamera = false , |
|
|
PointCloudROI const * |
roi = nullptr |
|
) |
| |
◆ pointCloudWithNormalsFromNxLib()
std::unique_ptr<ensenso::pcl::PointCloudNormals> pointCloudWithNormalsFromNxLib |
( |
NxLibItem const & |
pointMapNode, |
|
|
NxLibItem const & |
normalNode, |
|
|
std::string const & |
frame, |
|
|
bool |
isFileCamera = false , |
|
|
PointCloudROI const * |
roi = nullptr |
|
) |
| |
◆ retrieveRenderedDepthMap()
◆ retrieveRenderedPointCloud()
std::unique_ptr<ensenso::pcl::PointCloud> retrieveRenderedPointCloud |
( |
NxLibItem const & |
cmdResult, |
|
|
std::string const & |
frame, |
|
|
bool |
isFileCamera = false |
|
) |
| |
◆ retrieveTexturedPointCloud()
std::unique_ptr<ensenso::pcl::PointCloudColored> retrieveTexturedPointCloud |
( |
NxLibItem const & |
cmdResult, |
|
|
std::string const & |
targetFrame, |
|
|
bool |
isFileCamera = false |
|
) |
| |
◆ setRenderParams()