ros2 / rmw_cyclonedds

ROS 2 RMW layer for Eclipse Cyclone DDS
Apache License 2.0
111 stars 91 forks source link

ROS service not receiving native DDS requests correctly #503

Open tmayoff opened 2 months ago

tmayoff commented 2 months ago

Bug report

Required Info:

Steps to reproduce issue

  1. Setup node and service
Transformer::Transformer() : rclcpp::Node("transformer"), tf_listener(nullptr) {
  this->get_logger().set_level(rclcpp::Logger::Level::Debug);

  tf_buffer = std::make_unique<tf2_ros::Buffer>(this->get_clock());
  tf_listener = std::make_shared<tf2_ros::TransformListener>(*tf_buffer);

  raycast_pose = this->create_publisher<geometry_msgs::msg::PoseStamped>("/looking_at", 10);

  transform_service = this->create_service<avatar_msgs::srv::TransformPoint>(
      "transformer", [this](const avatar_msgs::srv::TransformPoint::Request::SharedPtr request,
                            avatar_msgs::srv::TransformPoint::Response::SharedPtr response) { service_callback(request, response); });
}

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

  auto node = std::make_shared<Transformer>();
  rclcpp::spin(node);
  rclcpp::shutdown();

  return 0;
}
string source_frame
string target_frame
geometry_msgs/Transform input
---
geometry_msgs/Transform output
bool valid
#ifndef TRANSFORMER_REQUEST_IDL
#define TRANSFORMER_REQUEST_IDL

#include "geometry_msgs/msg/Transform.idl"

module avatar_msgs {
  module srv {
    module dds_ {
      @final @topic struct TransformPoint_Request_ {
        string source_frame;
        string target_frame;
        geometry_msgs::msg::dds_::Transform_ input;
      };
    };
  };
};

#endif  // TRANSFORMER_REQUEST_IDL
#ifndef TRANSFORMER_RESPONSE_IDL
#define TRANSFORMER_RESPONSE_IDL

#include "geometry_msgs/msg/Transform.idl"

module avatar_msgs {
  module srv {
    module dds_ {
      @final @topic struct TransformPoint_Response_ {
        geometry_msgs::msg::dds_::Transform_ output;
        boolean valid;
      };
    };
  };
};

#endif  // TRANSFORMER_RESPONSE_IDL

The native dds client code is a bit more scattered (wrapper around cyclonedds-cxx), I can provide it if required.

Expected behavior

The request object should contain the details sent by the client and respond accordingly.

Actual behavior

When sending a request to the service it's received in the node, but the request object is default initialized, none of the fields are field with the data that was sent. The service callback fails, and returns a not properly initialized response (transform output contains random values).

Additional information

These were grabbed off cyclonedds' cli tool once with just ROS2 running and the other with just the native dds application

╭─────────────────────────────────────────────────────────────────── Participant 0110edfe-348a-18e7-e724-7cad000001c1 ───────────────────────────────────────────────────────────────────╮
│                                                                                                                                                                                        │
│ ╭───────────────────────────────  QoS ───────────────────────────────╮                                                                                                                 │
│ │ Liveliness.Automatic(lease_duration='10 seconds')                  │                                                                                                                 │
│ │ Property(key='__Hostname', value='')                      │                                                                                                                 │
│ │ Property(key='__NetworkAddresses', value='udp/10.0.0.199:44150@3') │                                                                                                                 │
│ │ Property(key='__Pid', value='201533')                              │                                                                                                                 │
│ │ Property(key='__ProcessName', value='transformer')                 │                                                                                                                 │
│ │ Userdata(data=b'enclave=/;')                                       │                                                                                                                 │
│ ╰────────────────────────────────────────────────────────────────────╯                                                                                                                 │
│                                                                                                                                                                                        │
│ ╭────────────────────────────────────────────────────────────────────────────── rq/transformerRequest ───────────────────────────────────────────────────────────────────────────────╮ │
│ │ ╭────────────────────────────────────────────────────────────────────────────────── Common QoS ──────────────────────────────────────────────────────────────────────────────────╮ │ │
│ │ │ DataRepresentation(use_cdrv0_representation=True, use_xcdrv2_representation=False)                                                                                             │ │ │
│ │ │ Deadline(deadline='infinity')                                                                                                                                                  │ │ │
│ │ │ DestinationOrder.ByReceptionTimestamp                                                                                                                                          │ │ │
│ │ │ Durability.Volatile                                                                                                                                                            │ │ │
│ │ │ History.KeepLast(depth=10)                                                                                                                                                     │ │ │
│ │ │ IgnoreLocal.Nothing                                                                                                                                                            │ │ │
│ │ │ LatencyBudget(budget='zero')                                                                                                                                                   │ │ │
│ │ │ Liveliness.Automatic(lease_duration='infinity')                                                                                                                                │ │ │
│ │ │ Ownership.Shared                                                                                                                                                               │ │ │
│ │ │ PresentationAccessScope.Instance(coherent_access=False, ordered_access=False)                                                                                                  │ │ │
│ │ │ ReaderDataLifecycle(autopurge_nowriter_samples_delay='infinity', autopurge_disposed_samples_delay='infinity')                                                                  │ │ │
│ │ │ Reliability.Reliable(max_blocking_time='infinity')                                                                                                                             │ │ │
│ │ │ ResourceLimits(max_samples=-1, max_instances=-1, max_samples_per_instance=-1)                                                                                                  │ │ │
│ │ │ TimeBasedFilter(filter_time='zero')                                                                                                                                            │ │ │
│ │ │ TransportPriority(priority=0)                                                                                                                                                  │ │ │
│ │ │ TypeConsistency.AllowTypeCoercion(ignore_sequence_bounds=True, ignore_string_bounds=True, ignore_member_names=False, prevent_type_widening=False, force_type_validation=False) │ │ │
│ │ │ Userdata(data=b'serviceid= 1.10.ed.fe.34.8a.18.e7.e7.24.7c.ad.0.0.0.7;')                                                                                                       │ │ │
│ │ ╰────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────╯ │ │
│ │ ┌────────────────┬─────────────────────────────────────────────────┐                                                                                                               │ │
│ │ │ Typename       │ avatar_msgs::srv::dds_::TransformPoint_Request_ │                                                                                                               │ │
│ │ │ XTypes Type ID │                                           unset │                                                                                                               │ │
│ │ └────────────────┴─────────────────────────────────────────────────┘                                                                                                               │ │
│ │              Subscriptions                                                                                                                                                         │ │
│ │ ┏━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━┓                                                                                                                                           │ │
│ │ ┃ GUID                                 ┃                                                                                                                                           │ │
│ │ ┡━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━┩                                                                                                                                           │ │
│ │ │ 0110edfe-348a-18e7-e724-7cad00001d04 │                                                                                                                                           │ │
│ │ └──────────────────────────────────────┘                                                                                                                                           │ │
│ ╰────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────╯ │
╰────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────╯

╭────────────────────────────────────────────── Participant 01101a2e-0d3e-ba49-5cea-892e000001c1 ──────────────────────────────────────────────╮
│                                                                                                                                              │
│ ╭───────────────────────────────  QoS ───────────────────────────────╮                                                                       │
│ │ Liveliness.Automatic(lease_duration='10 seconds')                  │                                                                       │
│ │ Property(key='__Hostname', value='')                      │                                                                       │
│ │ Property(key='__NetworkAddresses', value='udp/10.0.0.199:54447@3') │                                                                       │
│ │ Property(key='__Pid', value='305120')                              │                                                                       │
│ │ Property(key='__ProcessName', value='')                 │                                                                       │
│ ╰────────────────────────────────────────────────────────────────────╯                                                                       │
│                                                                                                                                              │
│ ╭───────────────────────────────────────────────────────── rq/transformerRequest ──────────────────────────────────────────────────────────╮ │
│ │ ╭───────────────────────────────────────────────────────────── Common QoS ─────────────────────────────────────────────────────────────╮ │ │
│ │ │ DataRepresentation(use_cdrv0_representation=True, use_xcdrv2_representation=True)                                                    │ │ │
│ │ │ Deadline(deadline='infinity')                                                                                                        │ │ │
│ │ │ DestinationOrder.ByReceptionTimestamp                                                                                                │ │ │
│ │ │ Durability.Volatile                                                                                                                  │ │ │
│ │ │ DurabilityService(cleanup_delay=0, history=History.KeepLast(depth=1), max_samples=-1, max_instances=-1, max_samples_per_instance=-1) │ │ │
│ │ │ History.KeepAll                                                                                                                      │ │ │
│ │ │ IgnoreLocal.Nothing                                                                                                                  │ │ │
│ │ │ LatencyBudget(budget='zero')                                                                                                         │ │ │
│ │ │ Lifespan(lifespan='infinity')                                                                                                        │ │ │
│ │ │ Liveliness.Automatic(lease_duration='infinity')                                                                                      │ │ │
│ │ │ Ownership.Shared                                                                                                                     │ │ │
│ │ │ OwnershipStrength(strength=0)                                                                                                        │ │ │
│ │ │ PresentationAccessScope.Instance(coherent_access=False, ordered_access=False)                                                        │ │ │
│ │ │ Reliability.Reliable(max_blocking_time='100 milliseconds')                                                                           │ │ │
│ │ │ ResourceLimits(max_samples=-1, max_instances=-1, max_samples_per_instance=-1)                                                        │ │ │
│ │ │ TransportPriority(priority=0)                                                                                                        │ │ │
│ │ │ WriterDataLifecycle(autodispose=True)                                                                                                │ │ │
│ │ ╰──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────╯ │ │
│ │ ┌────────────────┬─────────────────────────────────────────────────┐                                                                     │ │
│ │ │ Typename       │ avatar_msgs::srv::dds_::TransformPoint_Request_ │                                                                     │ │
│ │ │ XTypes Type ID │           COMPLETE 7AB8E5650C79612B62E1F36D1635 │                                                                     │ │
│ │ └────────────────┴─────────────────────────────────────────────────┘                                                                     │ │
│ │               Publications                                                                                                               │ │
│ │ ┏━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━┓                                                                                                 │ │
│ │ ┃ GUID                                 ┃                                                                                                 │ │
│ │ ┡━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━━┩                                                                                                 │ │
│ │ │ 01101a2e-0d3e-ba49-5cea-892e00000203 │                                                                                                 │ │
│ │ └──────────────────────────────────────┘                                                                                                 │ │
│ ╰──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────╯ │
╰──────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────────╯
tmayoff commented 1 month ago

So I implemented the service in ROS using pub/subs instead and it works with the same client code (with updated topic names). I guess there's something I'm missing when setting up the clients (or probably less likely there's a bug here?) any help would be great

eboasson commented 1 month ago

@tmayoff could it be that your native DDS types don't account for the request/response headers that the Cyclone RMW layer injects?

The header type is

struct RequestHeader {
  uint64_t guid;
  int64_t seq;
};

The guid and seq just need to be unique.

tmayoff commented 1 month ago

That could be it, reverse engineering ROS topics/services is proving difficult (unless we're missing some tools we can use), we've been using an old repo that contains a bunch of ROS2 messages and services already converted to native .idl. There's no mention of RequestHeaders (and I'm assuming the Response ones are the same as the requests). I'll try adjusting our setup to include those.

Is there a reason this wouldn't cause an error or pub/sub mismatch if they're differing types