3D Representation

Point Cloud

Point cloud is an important type of geometry data structure.

  • Unstructured set of points
  • Spatial information is hard to capture
  • Notion of surface is unclear
    • You need to run algorithms to determine which set of points compose a surface
  • Point density is not uniform
  • Easy to get using commercial Sensors

We use PointNet.

Point Cloud to Voxel

  • Build a 3D grid of voxels in the scene
  • Average over points at each voxel
  • Ready to perform 3D convolutions

Voxel to Pillar

  • Average over the voxels in the same dimension
  • Ready to perform 2D convlutions

Storage Formats

I ran into this issue while trying to make my VR headset from scratch. Came up with a few ways:

  1. std::vector<Eigen::Vector3f> (bad because you can’t pass directly to cuda)
  2. float3*, this is a CUDA thing
  3. Eigen::Vector3f*
  4. Come up with your own type, but that would be difficult to wrap into cuda kernel

Storage file formats

Saw this in this ZED https://github.com/stereolabs/zed-opencv/blob/master/cpp/src/SaveDepth.cpp

void setPointCloudFormatName(int format) {
    switch (format) {
        case 0:
        PointCloud_format_ext = ".xyz";
        break;
        case  1:
        PointCloud_format_ext = ".pcd";
        break;
        case  2:
        PointCloud_format_ext = ".ply";
        break;
        case  3:
        PointCloud_format_ext = ".vtk";
        break;
        default:
        break;
    }
}

Generic ROS2 Transform Node

This ROS2 node takes in point clouds in a particular frame and republishes in a different frame

#include <memory>
#include <functional>
 
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"
#include "tf2_sensor_msgs/tf2_sensor_msgs.h"
 
class PointCloudTransformNode : public rclcpp::Node
{
public:
  PointCloudTransformNode() : Node("point_cloud_transform_node")
  {
    tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
    tf_listener_ = std::make_unique<tf2_ros::TransformListener>(*tf_buffer_);
 
    point_cloud_sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
        "point_cloud_optical", 10,
        std::bind(&PointCloudTransformNode::pointCloudCallback, this, std::placeholders::_1));
 
    point_cloud_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("point_cloud_canonical", 10);
  }
 
private:
  void pointCloudCallback(const sensor_msgs::msg::PointCloud2::SharedPtr msg)
  {
    geometry_msgs::msg::TransformStamped transform_stamped;
 
    try
    {
      transform_stamped = tf_buffer_->lookupTransform(
          "canonical_frame", msg->header.frame_id,
          msg->header.stamp, rclcpp::Duration(1, 0));
 
      sensor_msgs::msg::PointCloud2 output;
      tf2::doTransform(*msg, output, transform_stamped);
 
      point_cloud_pub_->publish(output);
    }
    catch (tf2::TransformException &ex)
    {
      RCLCPP_ERROR(this->get_logger(), "Could not transform point cloud: %s", ex.what());
    }
  }
 
  rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr point_cloud_sub_;
  rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr point_cloud_pub_;
  std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
  std::unique_ptr<tf2_ros::TransformListener> tf_listener_;
};
 
int main(int argc, char **argv)
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<PointCloudTransformNode>());
  rclcpp::shutdown();
  return 0;
}