Repository Summary
Checkout URI | https://github.com/ros-perception/point_cloud_transport.git |
VCS Type | git |
VCS Version | humble |
Last Updated | 2025-05-12 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Packages
Name | Version |
---|---|
point_cloud_transport | 1.0.18 |
point_cloud_transport_py | 1.0.18 |
README
point_cloud_transport
ROS2 Distro | Build Status | Package build |
---|---|---|
Rolling | ||
Jazzy | ||
Humble |
Description
point_cloud_transport is a ROS 2 package for subscribing to and publishing PointCloud2 messages via different transport layers. E.g. it can provide support for transporting point clouds in low-bandwidth environment using Draco compression library.
point_cloud_transport is NOT yet released as C++ source code and binary packages via ROS buildfarm.
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 2 Publishers and Subscribers. Using point_cloud_transport instead of the ROS 2 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 point_cloud_transport:
#include <rclcpp/rclcpp.hpp>
#include <point_cloud_transport/point_cloud_transport.hpp>
void Callback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg)
{
// ... process the message
}
auto node = std::make_shared<rclcpp::Node>();
point_cloud_transport::PointCloudTransport pct(node);
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);
Alternatively, you can use point_cloud_transport outside of ROS2.
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <point_cloud_transport/point_cloud_codec.hpp>
point_cloud_transport::PointCloudCodec codec;
sensor_msgs::msg::PointCloud2 msg;
// ... do some cool pointcloud generation stuff ...
// untyped version (outputs an rclcpp::SerializedMessage)
rclcpp::SerializedMessage serialized_msg;
bool success = codec.encode("draco", msg, serialized_msg);
// OR
// typed version (outputs whatever message your selected transport returns,
// for draco that is a point_cloud_interfaces::msg::CompressedPointCloud2)
point_cloud_interfaces::msg::CompressedPointCloud2 compressed_msg;
bool success = codec.encode("draco", msg, compressed_msg);
Republish rclcpp component
We provide a process to republish any topic speaking in a given transport to a different topic speaking a different transport. e.g. have it subscribe to a topic you recorded encoded using draco and publish it as a raw, decoded message
ros2 run point_cloud_transport republish --ros-args -p in_transport:=raw -p out_transport:=draco --remap in:=input_topic_name --remap out:=ouput_topic_name
Python
The functionality of point_cloud_transport
is also exposed to python via pybind11
and rclpy
serialization.
Please see publisher.py and subscriber.py for example usage.
Whitelist point cloud transport
This allows you to specify plugins you do want to load (a.k.a. whitelist them).
ros2 run point_cloud_transport_tutorial my_publisher --ros-args -p pct.point_cloud.enable_pub_plugins:=["point_cloud_transport/zlib"]
Known transports
- draco_point_cloud_transport: Lossy compression via Google
- zlib_point_cloud_transport: Lossless compression via Zlib compression.
- Did you write one? Don’t hesitate and send a pull request adding it to this list!
Authors
ROS 1 Version:
- Jakub Paplhám - Initial work - paplhjak
- Ing. Tomáš Petříček, Ph.D. - Supervisor - tpet
- Martin Pecka - Maintainer - peci1
ROS 2 Version:
- John D’Angelo - Port to ROS 2 and Maintainer - john-maidbot
- Alejandro Hernández - Port to ROS 2 and Maintainer - ahcorde
License
This project is licensed under the BSD License - see the LICENSE file for details.
Acknowledgments
- image_transport - Provided template of plugin interface
- Draco - Provided compression functionality
Support
For questions/comments please email the maintainer mentioned in package.xml
.
If you have found an error in this package, please file an issue at: https://github.com/ros-perception/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.
CONTRIBUTING
Any contribution that you make to this repository will be under the 3-Clause BSD License, as dictated by that license.
Repository Summary
Checkout URI | https://github.com/ros-perception/point_cloud_transport.git |
VCS Type | git |
VCS Version | jazzy |
Last Updated | 2025-05-12 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Packages
Name | Version |
---|---|
point_cloud_transport | 4.0.4 |
point_cloud_transport_py | 4.0.4 |
README
point_cloud_transport
ROS2 Distro | Build Status | Package build |
---|---|---|
Rolling | ||
Jazzy | ||
Humble |
Description
point_cloud_transport is a ROS 2 package for subscribing to and publishing PointCloud2 messages via different transport layers. E.g. it can provide support for transporting point clouds in low-bandwidth environment using Draco compression library.
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 2 Publishers and Subscribers. Using point_cloud_transport instead of the ROS 2 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 point_cloud_transport:
#include <rclcpp/rclcpp.hpp>
#include <point_cloud_transport/point_cloud_transport.hpp>
void Callback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg)
{
// ... process the message
}
auto node = std::make_shared<rclcpp::Node>();
point_cloud_transport::PointCloudTransport pct(node);
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);
Alternatively, you can use point_cloud_transport outside of ROS2.
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <point_cloud_transport/point_cloud_codec.hpp>
point_cloud_transport::PointCloudCodec codec;
sensor_msgs::msg::PointCloud2 msg;
// ... do some cool pointcloud generation stuff ...
// untyped version (outputs an rclcpp::SerializedMessage)
rclcpp::SerializedMessage serialized_msg;
bool success = codec.encode("draco", msg, serialized_msg);
// OR
// typed version (outputs whatever message your selected transport returns,
// for draco that is a point_cloud_interfaces::msg::CompressedPointCloud2)
point_cloud_interfaces::msg::CompressedPointCloud2 compressed_msg;
bool success = codec.encode("draco", msg, compressed_msg);
Republish rclcpp component
We provide a process to republish any topic speaking in a given transport to a different topic speaking a different transport. e.g. have it subscribe to a topic you recorded encoded using draco and publish it as a raw, decoded message
ros2 run point_cloud_transport republish --ros-args -p in_transport:=raw -p out_transport:=draco --remap in:=input_topic_name --remap out:=ouput_topic_name
Python
The functionality of point_cloud_transport
is also exposed to python via pybind11
and rclpy
serialization.
Please see publisher.py and subscriber.py for example usage.
Whitelist point cloud transport
This allows you to specify plugins you do want to load (a.k.a. whitelist them).
ros2 run point_cloud_transport_tutorial my_publisher --ros-args -p pct.point_cloud.enable_pub_plugins:=["point_cloud_transport/zlib"]
Known transports
- draco_point_cloud_transport: Lossy compression via Google
- zlib_point_cloud_transport: Lossless compression via Zlib compression.
- zstd_point_cloud_transport: Lossless compression via Zstd compression.
- Did you write one? Don’t hesitate and send a pull request adding it to this list!
Authors
ROS 1 Version:
- Jakub Paplhám - Initial work - paplhjak
- Ing. Tomáš Petříček, Ph.D. - Supervisor - tpet
- Martin Pecka - Maintainer - peci1
ROS 2 Version:
- John D’Angelo - Port to ROS 2 and Maintainer - john-maidbot
- Alejandro Hernández - Port to ROS 2 and Maintainer - ahcorde
License
This project is licensed under the BSD License - see the LICENSE file for details.
Acknowledgments
- image_transport - Provided template of plugin interface
- Draco - Provided compression functionality
Support
For questions/comments please email the maintainer mentioned in package.xml
.
If you have found an error in this package, please file an issue at: https://github.com/ros-perception/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.
CONTRIBUTING
Any contribution that you make to this repository will be under the 3-Clause BSD License, as dictated by that license.
Repository Summary
Checkout URI | https://github.com/ros-perception/point_cloud_transport.git |
VCS Type | git |
VCS Version | kilted |
Last Updated | 2025-05-12 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Packages
Name | Version |
---|---|
point_cloud_transport | 5.1.3 |
point_cloud_transport_py | 5.1.3 |
README
point_cloud_transport
ROS2 Distro | Build Status | Package build |
---|---|---|
Rolling | ||
Jazzy | ||
Humble |
Description
point_cloud_transport is a ROS 2 package for subscribing to and publishing PointCloud2 messages via different transport layers. E.g. it can provide support for transporting point clouds in low-bandwidth environment using Draco compression library.
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 2 Publishers and Subscribers. Using point_cloud_transport instead of the ROS 2 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 point_cloud_transport:
#include <rclcpp/rclcpp.hpp>
#include <point_cloud_transport/point_cloud_transport.hpp>
void Callback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg)
{
// ... process the message
}
auto node = std::make_shared<rclcpp::Node>();
point_cloud_transport::PointCloudTransport pct(node);
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);
Alternatively, you can use point_cloud_transport outside of ROS2.
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <point_cloud_transport/point_cloud_codec.hpp>
point_cloud_transport::PointCloudCodec codec;
sensor_msgs::msg::PointCloud2 msg;
// ... do some cool pointcloud generation stuff ...
// untyped version (outputs an rclcpp::SerializedMessage)
rclcpp::SerializedMessage serialized_msg;
bool success = codec.encode("draco", msg, serialized_msg);
// OR
// typed version (outputs whatever message your selected transport returns,
// for draco that is a point_cloud_interfaces::msg::CompressedPointCloud2)
point_cloud_interfaces::msg::CompressedPointCloud2 compressed_msg;
bool success = codec.encode("draco", msg, compressed_msg);
Republish rclcpp component
We provide a process to republish any topic speaking in a given transport to a different topic speaking a different transport. e.g. have it subscribe to a topic you recorded encoded using draco and publish it as a raw, decoded message
ros2 run point_cloud_transport republish --ros-args -p in_transport:=raw -p out_transport:=draco --remap in:=input_topic_name --remap out:=ouput_topic_name
Python
The functionality of point_cloud_transport
is also exposed to python via pybind11
and rclpy
serialization.
Please see publisher.py and subscriber.py for example usage.
Whitelist point cloud transport
This allows you to specify plugins you do want to load (a.k.a. whitelist them).
ros2 run point_cloud_transport_tutorial my_publisher --ros-args -p pct.point_cloud.enable_pub_plugins:=["point_cloud_transport/zlib"]
Known transports
- draco_point_cloud_transport: Lossy compression via Google
- zlib_point_cloud_transport: Lossless compression via Zlib compression.
- zstd_point_cloud_transport: Lossless compression via Zstd compression.
- Did you write one? Don’t hesitate and send a pull request adding it to this list!
Authors
ROS 1 Version:
- Jakub Paplhám - Initial work - paplhjak
- Ing. Tomáš Petříček, Ph.D. - Supervisor - tpet
- Martin Pecka - Maintainer - peci1
ROS 2 Version:
- John D’Angelo - Port to ROS 2 and Maintainer - john-maidbot
- Alejandro Hernández - Port to ROS 2 and Maintainer - ahcorde
License
This project is licensed under the BSD License - see the LICENSE file for details.
Acknowledgments
- image_transport - Provided template of plugin interface
- Draco - Provided compression functionality
Support
For questions/comments please email the maintainer mentioned in package.xml
.
If you have found an error in this package, please file an issue at: https://github.com/ros-perception/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.
CONTRIBUTING
Any contribution that you make to this repository will be under the 3-Clause BSD License, as dictated by that license.
Repository Summary
Checkout URI | https://github.com/ros-perception/point_cloud_transport.git |
VCS Type | git |
VCS Version | rolling |
Last Updated | 2025-05-12 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Packages
Name | Version |
---|---|
point_cloud_transport | 5.2.0 |
point_cloud_transport_py | 5.2.0 |
README
point_cloud_transport
ROS2 Distro | Build Status | Package build |
---|---|---|
Rolling | ||
Jazzy | ||
Humble |
Description
point_cloud_transport is a ROS 2 package for subscribing to and publishing PointCloud2 messages via different transport layers. E.g. it can provide support for transporting point clouds in low-bandwidth environment using Draco compression library.
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 2 Publishers and Subscribers. Using point_cloud_transport instead of the ROS 2 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 point_cloud_transport:
#include <rclcpp/rclcpp.hpp>
#include <point_cloud_transport/point_cloud_transport.hpp>
void Callback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg)
{
// ... process the message
}
auto node = std::make_shared<rclcpp::Node>();
point_cloud_transport::PointCloudTransport pct(node);
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);
Alternatively, you can use point_cloud_transport outside of ROS2.
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <point_cloud_transport/point_cloud_codec.hpp>
point_cloud_transport::PointCloudCodec codec;
sensor_msgs::msg::PointCloud2 msg;
// ... do some cool pointcloud generation stuff ...
// untyped version (outputs an rclcpp::SerializedMessage)
rclcpp::SerializedMessage serialized_msg;
bool success = codec.encode("draco", msg, serialized_msg);
// OR
// typed version (outputs whatever message your selected transport returns,
// for draco that is a point_cloud_interfaces::msg::CompressedPointCloud2)
point_cloud_interfaces::msg::CompressedPointCloud2 compressed_msg;
bool success = codec.encode("draco", msg, compressed_msg);
Republish rclcpp component
We provide a process to republish any topic speaking in a given transport to a different topic speaking a different transport. e.g. have it subscribe to a topic you recorded encoded using draco and publish it as a raw, decoded message
ros2 run point_cloud_transport republish --ros-args -p in_transport:=raw -p out_transport:=draco --remap in:=input_topic_name --remap out:=ouput_topic_name
Python
The functionality of point_cloud_transport
is also exposed to python via pybind11
and rclpy
serialization.
Please see publisher.py and subscriber.py for example usage.
Whitelist point cloud transport
This allows you to specify plugins you do want to load (a.k.a. whitelist them).
ros2 run point_cloud_transport_tutorial my_publisher --ros-args -p pct.point_cloud.enable_pub_plugins:=["point_cloud_transport/zlib"]
Known transports
- draco_point_cloud_transport: Lossy compression via Google
- zlib_point_cloud_transport: Lossless compression via Zlib compression.
- zstd_point_cloud_transport: Lossless compression via Zstd compression.
- Did you write one? Don’t hesitate and send a pull request adding it to this list!
Authors
ROS 1 Version:
- Jakub Paplhám - Initial work - paplhjak
- Ing. Tomáš Petříček, Ph.D. - Supervisor - tpet
- Martin Pecka - Maintainer - peci1
ROS 2 Version:
- John D’Angelo - Port to ROS 2 and Maintainer - john-maidbot
- Alejandro Hernández - Port to ROS 2 and Maintainer - ahcorde
License
This project is licensed under the BSD License - see the LICENSE file for details.
Acknowledgments
- image_transport - Provided template of plugin interface
- Draco - Provided compression functionality
Support
For questions/comments please email the maintainer mentioned in package.xml
.
If you have found an error in this package, please file an issue at: https://github.com/ros-perception/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.
CONTRIBUTING
Any contribution that you make to this repository will be under the 3-Clause BSD License, as dictated by that license.
Repository Summary
Checkout URI | https://github.com/ros-perception/point_cloud_transport.git |
VCS Type | git |
VCS Version | iron |
Last Updated | 2024-09-24 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Packages
Name | Version |
---|---|
point_cloud_transport | 2.0.6 |
point_cloud_transport_py | 2.0.6 |
README
point_cloud_transport
ROS2 Distro | Build Status | Package build |
---|---|---|
Rolling | ||
Jazzy | ||
Iron | ||
Humble |
Description
point_cloud_transport is a ROS 2 package for subscribing to and publishing PointCloud2 messages via different transport layers. E.g. it can provide support for transporting point clouds in low-bandwidth environment using Draco compression library.
point_cloud_transport is NOT yet released as C++ source code and binary packages via ROS buildfarm.
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 2 Publishers and Subscribers. Using point_cloud_transport instead of the ROS 2 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 point_cloud_transport:
#include <rclcpp/rclcpp.hpp>
#include <point_cloud_transport/point_cloud_transport.hpp>
void Callback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr& msg)
{
// ... process the message
}
auto node = std::make_shared<rclcpp::Node>();
point_cloud_transport::PointCloudTransport pct(node);
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);
Alternatively, you can use point_cloud_transport outside of ROS2.
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <point_cloud_transport/point_cloud_codec.hpp>
point_cloud_transport::PointCloudCodec codec;
sensor_msgs::msg::PointCloud2 msg;
// ... do some cool pointcloud generation stuff ...
// untyped version (outputs an rclcpp::SerializedMessage)
rclcpp::SerializedMessage serialized_msg;
bool success = codec.encode("draco", msg, serialized_msg);
// OR
// typed version (outputs whatever message your selected transport returns,
// for draco that is a point_cloud_interfaces::msg::CompressedPointCloud2)
point_cloud_interfaces::msg::CompressedPointCloud2 compressed_msg;
bool success = codec.encode("draco", msg, compressed_msg);
Republish rclcpp component
We provide a process to republish any topic speaking in a given transport to a different topic speaking a different transport. e.g. have it subscribe to a topic you recorded encoded using draco and publish it as a raw, decoded message
ros2 run point_cloud_transport republish --ros-args -p in_transport:=raw -p out_transport:=draco --remap in:=input_topic_name --remap out:=ouput_topic_name
Python
The functionality of point_cloud_transport
is also exposed to python via pybind11
and rclpy
serialization.
Please see point_cloud_transport/publisher.py and point_cloud_transport/subscriber.py for example usage.
Whitelist point cloud transport
This allows you to specify plugins you do want to load (a.k.a. whitelist them).
ros2 run point_cloud_transport_tutorial my_publisher --ros-args -p pct.point_cloud.enable_pub_plugins:=["point_cloud_transport/zlib"]
Known transports
- draco_point_cloud_transport: Lossy compression via Google
- zlib_point_cloud_transport: Lossless compression via Zlib compression.
- Did you write one? Don’t hesitate and send a pull request adding it to this list!
Authors
ROS 1 Version:
- Jakub Paplhám - Initial work - paplhjak
- Ing. Tomáš Petříček, Ph.D. - Supervisor - tpet
- Martin Pecka - Maintainer - peci1
ROS 2 Version:
- John D’Angelo - Port to ROS 2 and Maintainer - john-maidbot
- Alejandro Hernández - Port to ROS 2 and Maintainer - ahcorde
License
This project is licensed under the BSD License - see the LICENSE file for details.
Acknowledgments
- image_transport - Provided template of plugin interface
- Draco - Provided compression functionality
Support
For questions/comments please email the maintainer mentioned in package.xml
.
If you have found an error in this package, please file an issue at: https://github.com/ros-perception/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.
CONTRIBUTING
Any contribution that you make to this repository will be under the 3-Clause BSD License, as dictated by that license.