Skip to content

Segmentation fault occurs with Type Adapter when using large data size in ROS message #2417

@allbluelai

Description

@allbluelai

Bug report

Required Info:

  • Operating System:
    • Ubuntu 22.04
  • Installation type:
    • source install
  • DDS implementation:
    • test on Fast-RTPS, CycloneDDS, iceoryx DDS
  • Client library (if applicable):
    • rclcpp

Steps to reproduce issue

TestMsg.msg:

# uint32[1048576] data # work fine
uint32[2097152] data # fail
uint8[128] name
uint8 name_size

myString.hpp:

#ifndef MY_STRING_HPP
#define MY_STRING_HPP

#include "rclcpp/rclcpp.hpp"
#include "tutorial_interfaces/msg/test_msg.hpp"

template <>
struct rclcpp::TypeAdapter<
    std::string,
    tutorial_interfaces::msg::TestMsg>
{
  using is_specialized = std::true_type;
  using custom_type = std::string;
  using ros_message_type = tutorial_interfaces::msg::TestMsg;

  static void
  convert_to_ros_message(
      const custom_type &source,
      ros_message_type &destination)
  {
    std::memcpy(destination.name.data(), source.data(), source.size());
    destination.name_size = source.size();
  }

  static void
  convert_to_custom(
      const ros_message_type &source,
      custom_type &destination)
  {
    destination.resize(source.name_size);
    std::memcpy(destination.data(), source.name.data(), source.name_size);
  }
};

RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(std::string, tutorial_interfaces::msg::TestMsg);

#endif // !MY_STRING_HPP

Here, std::string is a custom type.

pub.cpp:

#include <chrono>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "myString.hpp"

using namespace std::chrono_literals;
using TopicPub = std::string;

class MinimalPublisher : public rclcpp::Node
{
public:
  MinimalPublisher()
      : Node("minimal_publisher"), count_(0)
  {
    auto timer_callback =
        [this]() -> void
    {
      std::string name = "myName";
      this->publisher_->publish(name);
    };

    publisher_ = this->create_publisher<TopicPub>("topic", 10);
    timer_ = create_wall_timer(30ms, timer_callback);
  }

private:
  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::Publisher<TopicPub>::SharedPtr publisher_;
  size_t count_;
};

int main(int argc, char *argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalPublisher>());
  rclcpp::shutdown();
  return 0;
}

sub.cpp:

#include <memory>
#include "rclcpp/rclcpp.hpp"
#include <chrono>
#include "myString.hpp"

using TopicSub = std::string;

class MinimalSubscriber : public rclcpp::Node
{
public:
  MinimalSubscriber()
      : Node("minimal_subscriber")
  {
    auto callback = [this](const TopicSub &msg)
    {
      std::cout << "msg = " << msg << std::endl;
    };

    subscription_ = this->create_subscription<TopicSub>("topic", 10, callback);
  }

private:
  rclcpp::Subscription<TopicSub>::SharedPtr subscription_;
};

int main(int argc, char *argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<MinimalSubscriber>());
  rclcpp::shutdown();
  return 0;
}

Expected behavior

Message sent successfully in the publisher and received in the subscriber.

Actual behavior

[ros2run]: Segmentation fault in the publisher.

Additional information

In TestMsg.msg, I define two different data size messages (1MB and 2MB). It works well with 1MB but fails with 2MB.

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't workinghelp wantedExtra attention is needed

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions