Class PointCloud2ImageNode

Inheritance Relationships

Base Type

  • public rclcpp::Node

Class Documentation

class PointCloud2ImageNode : public rclcpp::Node

Class implementing the node to fuse a point cloud and a camera image by projecting the geometric 3D information from the point cloud into the camera image.

Public Functions

PointCloud2ImageNode(rclcpp::NodeOptions iNodeOptions, std::string iNodeName = "pointcloud2image")

Default Constructor.

virtual ~PointCloud2ImageNode()

Default Destructor.

void computeCameraPoseForFrustumCulling(const lib3d::Camera &iCamera, Eigen::Matrix4f &oFrustumCullingPose) const

Method to compute the camera pose for the pcl::FrustumCulling algorithm.

Parameters:
  • iCamera[in] Camera object.

  • oFrustumCullingPose[out] 4x4 Matrix specifying camera pose

void doFrustumCulling(const pcl::PointCloud<InputPointType>::Ptr &ipCloud, const lib3d::Camera &iCamera, const float &iMinDepth, const float &iMaxDepth, pcl::Indices &oCulledPointIndices) const

Perform frustum culling on point cloud given teh camera object.

Parameters:
  • ipCloud[in] Pointer to input cloud

  • iCamera[in] Camera object

  • iMinDepth[in] Minumum depth

  • iMaxDepth[in] Maximum depth

  • oCulledPointIndices[out] List of point indices that are within the view frustum of the camera.

void onSensorDataReceived(const InputImage_Message_T::ConstSharedPtr &ipImgMsg, const InputCloud_Message_T::ConstSharedPtr &ipCloudMsg)

This will use the point cloud and project it into the camera image where each projected point is colorized based on its depth with respect to the camera.

The colorization is performed by applying the RAINBOW colormap from .

In order to reduce the size of the point cloud prior to projecting it into the camera image, a frustum culling is performed.

void onCalibrationReceived(const CalibrationResult_Message_T::ConstSharedPtr &ipCalibMsg)

Callback for the calibration subscription. Will update the temp transofrm.

void onInit()

The onInit method is called by node manager. It is responsible for initializing the node.

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Note

It is important that this method returns, otherwise the node gets stuck during the initialization