/point_cloud_transport

point_cloud_transport provides classes and nodes for transporting point clouds in arbitrary over-the-wire representations, while abstracting this complexity so that the developer only sees sensor_msgs/PointCloud2 messages.

Primary LanguageC++BSD 3-Clause "New" or "Revised" LicenseBSD-3-Clause

<POINT CLOUD TRANSPORT>

v0.1. 1st BETA release version

Contents

Description

<point_cloud_transport> is a ROS package for subscribing to and publishing PointCloud2 messages. It provides support for transporting point clouds in low-bandwidth environment using Draco compression library.

<point_cloud_transport> is released as C++ source code.

Getting Started

Installation

Prerequisites

Setting up ROS workspace

Commands for creating workspace directory and cloning all necessary repositories:

$ mkdir -p point_cloud_transport_ws/src
$ cd point_cloud_transport_ws/src
$ git clone https://github.com/paplhjak/draco.git
$ git clone https://github.com/paplhjak/point_cloud_transport.git
$ git clone https://github.com/paplhjak/draco_point_cloud_transport.git
$ git clone https://github.com/paplhjak/point_cloud_transport_plugins.git

Building project

Commands for setting up catkin workspace and building the project:

$ cd ..
$ catkin init
$ catkin config --extend /opt/ros/melodic
$ catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release
$ catkin build

To build the project without Catkin Command Line Tools use the following command in the root of the workspace:

$ catkin_make_isolated

Dependencies

  • ROS Melodic Morenia - Framework
  • Draco 1.3.5 - Compression library
  • Catkin tools - Command line tools for working with the catkin meta-buildsystem and catkin workspaces

Usage

<point_cloud_transport> can be used to publish and subscribe to PointCloud2 messages. At this level of usage, it is similar to using ROS Publishers and Subscribers. Using <point_cloud_transport> instead of the ROS primitives, however, gives the user much greater flexibility in how point clouds are communicated between nodes.

For complete examples of publishing and subscribing to point clouds using <point_cloud_transport> , see Tutorial.

C++

Communicating PointCloud2 messages using base ROS publishers and subscribers:

#include <ros/ros.h>

void Callback(const sensor_msgs::PointCloud2ConstPtr& msg)
{
  // ... process the message
}

ros::NodeHandle nh;
ros::Subscriber sub = nh.subscribe("in_point_cloud_topic", 1, Callback);
ros::Publisher pub = nh.advertise<sensor_msgs::PointCloud2>("out_point_cloud_topic", 1);

Communicating PointCloud2 messages using <point_cloud_transport>:

#include <ros/ros.h>
#include <point_cloud_transport/point_cloud_transport.h>

void Callback(const sensor_msgs::PointCloud2ConstPtr& msg)
{
  // ... process the message
}

ros::NodeHandle nh;
point_cloud_transport::PointCloudTransport pct(nh);
point_cloud_transport::Subscriber sub = pct.subscribe("in_point_cloud_base_topic", 1, Callback);
point_cloud_transport::Publisher pub = pct.advertise("out_point_cloud_base_topic", 1);

Additional Information

Authors

  • Jakub Paplhám - Initial work - paplhjak
  • Ing. Tomáš Petříček, Ph.D. - Supervisor - tpet

See also the list of contributors.

License

This project is licensed under the BSD License - see the LICENSE.md file for details.

Acknowledgments

Support

For questions/comments please email paplhjak@fel.cvut.cz

If you have found an error in this package, please file an issue at:
https://github.com/paplhjak/point_cloud_transport/issues

Patches are encouraged, and may be submitted by forking this project and submitting a pull request through GitHub. Any help is further development of the project is much appreciated.