Repo symbol

point_cloud_transport_tutorial repository

Repository Summary

Checkout URI https://github.com/ros-perception/point_cloud_transport_tutorial.git
VCS Type git
VCS Version jazzy
Last Updated 2025-05-03
Dev Status MAINTAINED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
point_cloud_transport_tutorial 0.0.2

README

<POINT CLOUD TRANSPORT TUTORIAL>

ROS2 v0.1.

Contents

Writing a Simple Publisher

In this section, we’ll see how to create a publisher node, which opens a ROS 2 bag and publishes PointCloud2 messages from it.

This tutorial assumes that you have created your workspace containing [](https://github.com/ros-perception/point_cloud_transport) and [](https://github.com/ros-perception/point_cloud_transport_plugins)

Before we start, change to the directory, clone this repository, and unzip the example rosbag in the resources folder:

$ cd ~/<point_cloud_transport_ws>/src
$ git clone https://github.com/ros-perception/point_cloud_transport_tutorial
$ cd point_cloud_transport_tutorial
$ tar -C resources/ -xvf resources/rosbag2_2023_08_05-16_08_51.tar.xz
$ cd ~/<point_cloud_transport_ws>
$ colcon build --merge-install --event-handlers console_direct+

Code of the Publisher

Take a look at my_publisher.cpp

#include <point_cloud_transport/point_cloud_transport.hpp>

// for reading rosbag
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <rclcpp/serialization.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rosbag2_cpp/reader.hpp>
#include <rosbag2_cpp/storage_options.hpp>
#include <rosbag2_cpp/converter_interfaces/serialization_format_converter.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);

  auto node = std::make_shared<rclcpp::Node>("point_cloud_publisher");

  point_cloud_transport::PointCloudTransport pct(node);
  point_cloud_transport::Publisher pub = pct.advertise("pct/point_cloud", 100);

  const std::string bagged_cloud_topic = "/point_cloud";
  const std::string shared_directory = ament_index_cpp::get_package_share_directory(
    "point_cloud_transport_tutorial");
  const std::string bag_file = shared_directory + "/resources/rosbag2_2023_08_05-16_08_51";

  // boiler-plate to tell rosbag2 how to read our bag
  rosbag2_storage::StorageOptions storage_options;
  storage_options.uri = bag_file;
  storage_options.storage_id = "mcap";
  rosbag2_cpp::ConverterOptions converter_options;
  converter_options.input_serialization_format = "cdr";
  converter_options.output_serialization_format = "cdr";

  // open the rosbag
  rosbag2_cpp::readers::SequentialReader reader;
  reader.open(storage_options, converter_options);

  sensor_msgs::msg::PointCloud2 cloud_msg;
  rclcpp::Serialization<sensor_msgs::msg::PointCloud2> cloud_serialization;
  while (reader.has_next() && rclcpp::ok()) {
    // get serialized data
    auto serialized_message = reader.read_next();
    rclcpp::SerializedMessage extracted_serialized_msg(*serialized_message->serialized_data);
    if (serialized_message->topic_name == bagged_cloud_topic) {
      // deserialize and convert to  message
      cloud_serialization.deserialize_message(&extracted_serialized_msg, &cloud_msg);
      // publish the message
      pub.publish(cloud_msg);
      rclcpp::spin_some(node);
      rclcpp::sleep_for(std::chrono::milliseconds(100));
    }
  }
  reader.close();

  node.reset();
  rclcpp::shutdown();
}

Code of Publisher Explained

Now we’ll break down the code piece by piece.

Header for including [](https://github.com/ros-perception/point_cloud_transport):

File truncated at 100 lines see the full file

CONTRIBUTING

Any contribution that you make to this repository will be under the 3-Clause BSD License, as dictated by that license.

Any contribution that you make to this repository will be under the 3-Clause BSD License, as dictated by that [license](https://opensource.org/licenses/BSD-3-Clause).

Repository Summary

Checkout URI https://github.com/ros-perception/point_cloud_transport_tutorial.git
VCS Type git
VCS Version kilted
Last Updated 2025-05-03
Dev Status MAINTAINED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
point_cloud_transport_tutorial 0.0.2

README

<POINT CLOUD TRANSPORT TUTORIAL>

ROS2 v0.1.

Contents

Writing a Simple Publisher

In this section, we’ll see how to create a publisher node, which opens a ROS 2 bag and publishes PointCloud2 messages from it.

This tutorial assumes that you have created your workspace containing [](https://github.com/ros-perception/point_cloud_transport) and [](https://github.com/ros-perception/point_cloud_transport_plugins)

Before we start, change to the directory, clone this repository, and unzip the example rosbag in the resources folder:

$ cd ~/<point_cloud_transport_ws>/src
$ git clone https://github.com/ros-perception/point_cloud_transport_tutorial
$ cd point_cloud_transport_tutorial
$ tar -C resources/ -xvf resources/rosbag2_2023_08_05-16_08_51.tar.xz
$ cd ~/<point_cloud_transport_ws>
$ colcon build --merge-install --event-handlers console_direct+

Code of the Publisher

Take a look at my_publisher.cpp

#include <point_cloud_transport/point_cloud_transport.hpp>

// for reading rosbag
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <rclcpp/serialization.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rosbag2_cpp/reader.hpp>
#include <rosbag2_cpp/storage_options.hpp>
#include <rosbag2_cpp/converter_interfaces/serialization_format_converter.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);

  auto node = std::make_shared<rclcpp::Node>("point_cloud_publisher");

  point_cloud_transport::PointCloudTransport pct(node);
  point_cloud_transport::Publisher pub = pct.advertise("pct/point_cloud", 100);

  const std::string bagged_cloud_topic = "/point_cloud";
  const std::string shared_directory = ament_index_cpp::get_package_share_directory(
    "point_cloud_transport_tutorial");
  const std::string bag_file = shared_directory + "/resources/rosbag2_2023_08_05-16_08_51";

  // boiler-plate to tell rosbag2 how to read our bag
  rosbag2_storage::StorageOptions storage_options;
  storage_options.uri = bag_file;
  storage_options.storage_id = "mcap";
  rosbag2_cpp::ConverterOptions converter_options;
  converter_options.input_serialization_format = "cdr";
  converter_options.output_serialization_format = "cdr";

  // open the rosbag
  rosbag2_cpp::readers::SequentialReader reader;
  reader.open(storage_options, converter_options);

  sensor_msgs::msg::PointCloud2 cloud_msg;
  rclcpp::Serialization<sensor_msgs::msg::PointCloud2> cloud_serialization;
  while (reader.has_next() && rclcpp::ok()) {
    // get serialized data
    auto serialized_message = reader.read_next();
    rclcpp::SerializedMessage extracted_serialized_msg(*serialized_message->serialized_data);
    if (serialized_message->topic_name == bagged_cloud_topic) {
      // deserialize and convert to  message
      cloud_serialization.deserialize_message(&extracted_serialized_msg, &cloud_msg);
      // publish the message
      pub.publish(cloud_msg);
      rclcpp::spin_some(node);
      rclcpp::sleep_for(std::chrono::milliseconds(100));
    }
  }
  reader.close();

  node.reset();
  rclcpp::shutdown();
}

Code of Publisher Explained

Now we’ll break down the code piece by piece.

Header for including [](https://github.com/ros-perception/point_cloud_transport):

File truncated at 100 lines see the full file

CONTRIBUTING

Any contribution that you make to this repository will be under the 3-Clause BSD License, as dictated by that license.

Any contribution that you make to this repository will be under the 3-Clause BSD License, as dictated by that [license](https://opensource.org/licenses/BSD-3-Clause).

Repository Summary

Checkout URI https://github.com/ros-perception/point_cloud_transport_tutorial.git
VCS Type git
VCS Version rolling
Last Updated 2025-05-21
Dev Status MAINTAINED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
point_cloud_transport_tutorial 0.0.3

README

<POINT CLOUD TRANSPORT TUTORIAL>

ROS2 v0.1.

Contents

Writing a Simple Publisher

In this section, we’ll see how to create a publisher node, which opens a ROS 2 bag and publishes PointCloud2 messages from it.

This tutorial assumes that you have created your workspace containing [](https://github.com/ros-perception/point_cloud_transport) and [](https://github.com/ros-perception/point_cloud_transport_plugins)

Before we start, change to the directory, clone this repository, and unzip the example rosbag in the resources folder:

$ cd ~/<point_cloud_transport_ws>/src
$ git clone https://github.com/ros-perception/point_cloud_transport_tutorial
$ cd point_cloud_transport_tutorial
$ tar -C resources/ -xvf resources/rosbag2_2023_08_05-16_08_51.tar.xz
$ cd ~/<point_cloud_transport_ws>
$ colcon build --merge-install --event-handlers console_direct+

Code of the Publisher

Take a look at my_publisher.cpp

#include <point_cloud_transport/point_cloud_transport.hpp>

// for reading rosbag
#include <ament_index_cpp/get_package_share_directory.hpp>
#include <rclcpp/serialization.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rosbag2_cpp/reader.hpp>
#include <rosbag2_cpp/storage_options.hpp>
#include <rosbag2_cpp/converter_interfaces/serialization_format_converter.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);

  auto node = std::make_shared<rclcpp::Node>("point_cloud_publisher");

  point_cloud_transport::PointCloudTransport pct(node);
  point_cloud_transport::Publisher pub = pct.advertise("pct/point_cloud", 100);

  const std::string bagged_cloud_topic = "/point_cloud";
  const std::string shared_directory = ament_index_cpp::get_package_share_directory(
    "point_cloud_transport_tutorial");
  const std::string bag_file = shared_directory + "/resources/rosbag2_2023_08_05-16_08_51";

  // boiler-plate to tell rosbag2 how to read our bag
  rosbag2_storage::StorageOptions storage_options;
  storage_options.uri = bag_file;
  storage_options.storage_id = "mcap";
  rosbag2_cpp::ConverterOptions converter_options;
  converter_options.input_serialization_format = "cdr";
  converter_options.output_serialization_format = "cdr";

  // open the rosbag
  rosbag2_cpp::readers::SequentialReader reader;
  reader.open(storage_options, converter_options);

  sensor_msgs::msg::PointCloud2 cloud_msg;
  rclcpp::Serialization<sensor_msgs::msg::PointCloud2> cloud_serialization;
  while (reader.has_next() && rclcpp::ok()) {
    // get serialized data
    auto serialized_message = reader.read_next();
    rclcpp::SerializedMessage extracted_serialized_msg(*serialized_message->serialized_data);
    if (serialized_message->topic_name == bagged_cloud_topic) {
      // deserialize and convert to  message
      cloud_serialization.deserialize_message(&extracted_serialized_msg, &cloud_msg);
      // publish the message
      pub.publish(cloud_msg);
      rclcpp::spin_some(node);
      rclcpp::sleep_for(std::chrono::milliseconds(100));
    }
  }
  reader.close();

  node.reset();
  rclcpp::shutdown();
}

Code of Publisher Explained

Now we’ll break down the code piece by piece.

Header for including [](https://github.com/ros-perception/point_cloud_transport):

File truncated at 100 lines see the full file

CONTRIBUTING

Any contribution that you make to this repository will be under the 3-Clause BSD License, as dictated by that license.

Any contribution that you make to this repository will be under the 3-Clause BSD License, as dictated by that [license](https://opensource.org/licenses/BSD-3-Clause).
Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository

Repo symbol

point_cloud_transport_tutorial repository