ros2 / rclcpp

rclcpp (ROS Client Library for C++)
Apache License 2.0
514 stars 410 forks source link

Callback works on Galactic but fails on Rolling - handle_message is not implemented for GenericSubscription #2487

Closed sagunms closed 3 months ago

sagunms commented 3 months ago

I am trying to migrate my working ROS2 Galactic code since it is now EOL. I tested this on Rolling/Humble/Iron but non of them work. The API for using rclcpp::WaitSet with rclcpp::GenericSubscription seems to have changed.

Bug report

Required Info:

Steps to reproduce issue

#include "rclcpp/generic_subscription.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/serialization.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include "std_msgs/msg/string.hpp"
#include <memory>
using namespace std::chrono_literals;

int32_t main(const int32_t argc, char **const argv) {
  rclcpp::init(argc, argv);
  // Create node
  auto node = std::make_shared<rclcpp::Node>("wait_set_generic_subscription");
  // Subscription options
  auto sub_opt = rclcpp::SubscriptionOptions();
  sub_opt.callback_group = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
  // Create vector of subscriptions
  std::vector<rclcpp::GenericSubscription::SharedPtr> subscriptions;

  // Callback: works on Galactic but fails on Rolling (or Humble or Iron)
  auto callback = [](const std::shared_ptr<rclcpp::SerializedMessage> msg) -> void {
    std::cout << "Received data of length: " << std::dec << msg->size() << std::endl;
    std::cout << "Message type: No idea how to know this at runtime!!!" << std::endl;

    // // FIXME: How do we get the message type to be able get the concrete type?
    // // ROS1 had ShapeShifter library. How would I get the same behaviour in ROS2?
    // if( subscriptions.at(i)->get_message_type_somehow() == "std_msgs/msg/String" ) {
    //   std::cout << "It's a std_msgs/msg/String message so let me deserialize it!" << std::endl;
    // } else if( subscriptions.at(i)->get_message_type_somehow() == "sensor_msgs/msg/Imu" ) {
    //   std::cout << "It's a sensor_msgs/msg/Imu message so let me deserialize it!" << std::endl;
    // }
  };

  rclcpp::WaitSet wait_set;

  // NOTE: Subscribe to String and IMU messages 
  // say, these are only available at runtime e.g.. passed as cmd line arg or something. 
  subscriptions.emplace_back(
    node->create_generic_subscription("/topic/string", "std_msgs/msg/String", rclcpp::QoS(10), callback, sub_opt));
  wait_set.add_subscription(subscriptions.back());
  subscriptions.emplace_back(
    node->create_generic_subscription("/topic/imu", "sensor_msgs/msg/Imu", rclcpp::QoS(10), callback, sub_opt));
  wait_set.add_subscription(subscriptions.back());

  while (rclcpp::ok()) {
    const auto wait_result = wait_set.wait(3s);
    if (wait_result.kind() == rclcpp::WaitResultKind::Ready) {
      // Iterate over all subscriptions
      for (size_t i = 0; i < wait_set.get_rcl_wait_set().size_of_subscriptions; i++) {
        const auto *has_data = wait_result.get_wait_set().get_rcl_wait_set().subscriptions[i];
        if (!has_data) { continue; } // Skip if no data

        auto serialised_msg = subscriptions.at(i)->create_serialized_message();
        rclcpp::MessageInfo msg_info;
        if (subscriptions.at(i)->take_serialized(*serialised_msg, msg_info)) {
          const std::string topic_name = subscriptions.at(i)->get_topic_name();
          std::cout << std::endl << "Received message from topic: " << topic_name << std::endl;

          auto void_serialized_msg = std::static_pointer_cast<void>(serialised_msg);

          // FIXME: Getting error on Rolling but works fine on Galactic!
          // Error: terminate called after throwing an instance of 'rclcpp::exceptions::UnimplementedError'
          // what():  handle_message is not implemented for GenericSubscription
          subscriptions.at(i)->handle_message(void_serialized_msg, msg_info);
        }
      }
    } // Redacting else statement when wait_result.kind() is Timeout or Empty etc. 
  }
  rclcpp::shutdown();
  return 0;
}

Setup

Terminal 1: Publish String message at 2 Hz

ros2 topic pub /topic/string std_msgs/msg/String 'data: "I am a String message"' --rate 2

Terminal 2: Publish IMU message at 1 Hz

ros2 topic pub /topic/imu sensor_msgs/msg/Imu '{header: {frame_id: "I am an IMU message"} }' --rate 1

Terminal 3: Run built executable

Running the following creates two subscribers: /topic/string (std_msgs/msg/String) and /topic/imu (sensor_msgs/msg/Imu).

ros2 run wait_set_generic_subscription wait_set_generic_subscription 

Expected behavior

Received message from topic: /topic/string
Received data of length: 32
Message type: No idea how to know this at runtime!!!

Received message from topic: /topic/string
Received data of length: 32
Message type: No idea how to know this at runtime!!!

Received message from topic: /topic/imu
Received data of length: 332
Message type: No idea how to know this at runtime!!!

Actual behavior

Received message from topic: /topic/string

terminate called after throwing an instance of 'rclcpp::exceptions::UnimplementedError'
  what():  handle_message is not implemented for GenericSubscription
[ros2run]: Aborted
sagunms commented 3 months ago

FYI, when using GenericSubscription on later versions than ros-galactic, handle_serialized_message method should be used instead of handle_message.

On ros-galactic

auto void_serialized_msg = std::static_pointer_cast<void>(serialised_msg);
subscriptions.at(i)->handle_message(void_serialized_msg, msg_info);

On ros-humble, iron, rolling

subscriptions.at(i)->handle_serialized_message(serialized_msg, msg_info);