Skip to content

Add ROS2 Action support (client + server)#178

Open
comoc wants to merge 2 commits intoUnity-Technologies:main-ros2from
comoc:main-ros2
Open

Add ROS2 Action support (client + server)#178
comoc wants to merge 2 commits intoUnity-Technologies:main-ros2from
comoc:main-ros2

Conversation

@comoc
Copy link
Copy Markdown

@comoc comoc commented Apr 10, 2026

Proposed change(s)

Add ROS2 Action support to ROS-TCP-Endpoint. The stock endpoint cannot bridge ROS2 Actions because rclpy.action.ActionServer/ActionClient use a different DDS endpoint kind than plain services. This PR adds full bidirectional Action support.

Changes

resolve_message_name improvements:

  • Falls back to the "action" extension when "msg" or "srv" fails
  • Navigates rclpy nested Action class structure (Fibonacci.Impl.SendGoalService.Request etc.) via _try_resolve_action_class
  • Adds service-class entries (SendGoal, GetResult) to the suffix map
  • Handles 3-segment type names (pkg/action/Type) that __topic_list may report on reconnect

Action client protocol (new):

  • RosActionClient class wrapping rclpy.action.ActionClient
  • Syscommands: __action_client, __action_send_goal, __action_get_result, __action_cancel_goal
  • Futures polled with time.sleep to avoid executor ownership conflicts
  • Real goal UUID prepended to SendGoal response

Action server protocol (new):

  • RosActionServer class wrapping rclpy.action.ActionServer
  • Goal forwarded to TCP client via existing __request/__response mechanism
  • Feedback from client via __action_publish_feedback
  • Syscommands: __action_server, __action_publish_feedback

Additional:

  • send_ros_service_response_raw for pre-serialized CDR bytes
  • Feedback deduplication (uses __subscribe path only, no feedback_callback)

Useful links

Types of change(s)

  • Bug fix
  • New feature
  • Code refactor
  • Documentation update
  • Other

Testing and Verification

Tested end-to-end with action_tutorials_interfaces/Fibonacci action in both directions:

  1. TCP client as action client calling ROS2 fibonacci_action_server:

    • send_goal accepted, 9 feedback messages received, result [0,1,1,2,3,5,8,13,21,34,55] returned correctly
  2. ROS2 ros2 action send_goal calling TCP-client-implemented action server:

    • Goal received, 4 feedback messages published, result [0,1,1,2,3,5] returned with SUCCEEDED status
  3. Reconnect after endpoint restart: feedback subscription re-registered correctly with 3-segment type name handling

Test Configuration:

  • ROS machine OS + version: Ubuntu 22.04, ROS2 Humble
  • Endpoint: Built from this branch (main-ros2)
  • Action server: ros2 run action_tutorials_py fibonacci_action_server
  • TCP clients: both Unity (ROS-TCP-Connector) and custom GDScript client tested

Checklist

  • Ensured this PR is up-to-date with the main-ros2 branch
  • Created this PR to target the dev branch (Note: dev-ros2 has not been updated since 2022; targeting main-ros2 instead)
  • Followed the style guidelines as described in the Contribution Guidelines
  • Added tests that prove my fix is effective or that my feature works
  • Updated the Changelog
  • Updated the documentation as appropriate

Notes

The main-ros2 and dev-ros2 branches have not been updated since 2022, but the endpoint is still actively used by the community. This PR is offered as a contribution for anyone who needs Action support through the TCP bridge.

The implementation is backwards-compatible. Existing msg/srv lookups are completely unaffected. The action extension fallback and 3-segment name handling only trigger when the primary lookup fails.

New files:

  • ros_tcp_endpoint/action_client.py (RosActionClient)
  • ros_tcp_endpoint/action_server.py (RosActionServer)

Modified files:

  • ros_tcp_endpoint/server.py (syscommands + resolve_message_name)
  • ros_tcp_endpoint/client.py (action request routing)
  • ros_tcp_endpoint/tcp_sender.py (send_ros_service_response_raw)

comoc added 2 commits April 9, 2026 23:59
The stock ROS-TCP-Endpoint cannot bridge ROS2 Actions because
rclpy.action.ActionServer/Client use a different DDS endpoint kind
than plain services. This commit adds full Action support via new
syscommands and dedicated wrapper classes.

resolve_message_name improvements:
- Falls back to the "action" extension when the primary "msg" or
  "srv" lookup fails, so Action-generated types like
  Fibonacci_SendGoal can be resolved automatically.
- Navigates rclpy's nested Action class structure
  (Fibonacci.Impl.SendGoalService.Request etc.) transparently via
  _try_resolve_action_class, which maps flat wire names to nested
  attribute paths.
- Adds service-class entries (SendGoal, GetResult) to the suffix
  map so ros_service can discover Action service classes.

Action client protocol:
- New RosActionClient class (action_client.py) wrapping
  rclpy.action.ActionClient. Exposes send_goal, get_result, and
  cancel_goal as methods that accept CDR-serialized payloads.
- New syscommands: __action_client (registration), __action_send_goal,
  __action_get_result, __action_cancel_goal. Each sets pending state
  so the next data frame is routed to the appropriate method.
- Futures are polled with time.sleep instead of rclpy.spin_* to avoid
  executor ownership conflicts (the node is already owned by the
  TcpServer's MultiThreadedExecutor).
- The real goal UUID (assigned by rclpy internally) is prepended to
  the SendGoal response so the client can use it for get_result and
  cancel operations.

Action server protocol:
- New RosActionServer class (action_server.py) wrapping
  rclpy.action.ActionServer. When a ROS2 action client sends a goal,
  execute_callback serializes it as UUID + CDR Goal body and forwards
  it to the TCP client via __request/__response (same mechanism as
  unity_service).
- The TCP client can publish feedback via __action_publish_feedback
  (routed to goal_handle.publish_feedback) and set the result via
  __response (which unblocks execute_callback's ThreadPauser).
- New syscommands: __action_server (registration),
  __action_publish_feedback.

Additional fixes:
- send_ros_service_response_raw on UnityTcpSender for pre-serialized
  CDR bytes (Action methods do their own serialize_message internally).
- Feedback deduplication: removed feedback_callback from
  send_goal_async so feedback flows through the __subscribe topic
  path only, preventing double delivery.

Verified end-to-end: TCP client as action client calling a ROS2
Fibonacci action server (send_goal -> feedback -> result), and ROS2
action client calling a TCP-client-implemented action server.
When Unity reconnects after an endpoint restart, __topic_list reports
feedback topics with the full ROS2 type path including the extension
segment (e.g. "action_tutorials_interfaces/action/Fibonacci_FeedbackMessage").
Unity stores this as the topic's message name, and on reconnect sends
it back via __subscribe. The old 2-segment parser would split this
into module_name="action_tutorials_interfaces" and
class_name="action" (wrong), causing resolution failure.

Fix: detect 3-segment names where the middle segment is "msg", "srv",
or "action", extract it as the extension hint, and collapse the name
back to 2 segments before proceeding with normal resolution.
Copilot AI review requested due to automatic review settings April 10, 2026 03:42
@cla-assistant-unity
Copy link
Copy Markdown

CLA assistant check
Thank you for your submission! We really appreciate it. Like many open source projects, we ask that you sign our Contributor License Agreement before we can accept your contribution.
You have signed the CLA already but the status is still pending? Let us recheck it.

Copy link
Copy Markdown

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Adds ROS 2 Action bridging to ros_tcp_endpoint so TCP clients can act as action clients (calling native ROS 2 action servers) and/or implement action servers (serving native ROS 2 action clients), including improved type resolution for action-generated message/service types.

Changes:

  • Add RosActionClient and RosActionServer nodes plus new syscommands and routing logic for action goal/result/cancel/feedback flows.
  • Extend resolve_message_name to support action fallback, nested action sub-types, and 3-segment type names (pkg/action/Type).
  • Add send_ros_service_response_raw to send pre-serialized CDR payloads over the existing __response framing.

Reviewed changes

Copilot reviewed 5 out of 5 changed files in this pull request and generated 9 comments.

Show a summary per file
File Description
ros_tcp_endpoint/tcp_sender.py Adds raw CDR response sending for action-client operations.
ros_tcp_endpoint/server.py Adds action syscommands/tables and improves message/action type resolution.
ros_tcp_endpoint/client.py Routes action operations and action-server feedback frames from the TCP stream.
ros_tcp_endpoint/action_client.py New wrapper around rclpy.action.ActionClient returning CDR-serialized responses.
ros_tcp_endpoint/action_server.py New wrapper around rclpy.action.ActionServer forwarding goals/results via TCP and publishing feedback.

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

Comment on lines +90 to +101
future = self._action_client.send_goal_async(goal_msg)

# Wait for the send_goal future. Again, the executor is
# spinning on another thread, so we just poll the future.
for _ in range(100): # 10s max
if future.done():
break
time.sleep(0.1)
goal_handle = future.result()
if goal_handle is None:
return None

Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In send_goal, you poll the future for up to 10s but then call future.result() unconditionally. If the future never completed, result() will block indefinitely and defeats the intended timeout. Please guard with if not future.done(): and return an error/None (or cancel) on timeout before calling result().

Copilot uses AI. Check for mistakes.
for _ in range(3000): # 300s max
if result_future.done():
break
time.sleep(0.1)
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In get_result, after polling for up to 300s you still call result_future.result() even if the future is not done, which can block forever. Add an explicit timeout check (if not result_future.done(): ...) before calling result() and decide how to report a timeout to the TCP client.

Suggested change
time.sleep(0.1)
time.sleep(0.1)
if not result_future.done():
self.get_logger().error(
f"get_result: timed out waiting for result for UUID {key.hex()}")
with self._goal_handles_lock:
self._goal_handles.pop(key, None)
return None

Copilot uses AI. Check for mistakes.
for _ in range(100): # 10s max
if cancel_future.done():
break
time.sleep(0.1)
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In cancel_goal, you poll cancel_future for up to 10s but then call cancel_future.result() regardless of completion. If it didn't complete, this will block indefinitely. Please check cancel_future.done() and handle the timeout path before calling result().

Suggested change
time.sleep(0.1)
time.sleep(0.1)
if not cancel_future.done():
self.get_logger().error(
f"cancel_goal: timed out waiting for cancel response for UUID {key.hex()}")
return None

Copilot uses AI. Check for mistakes.
import re
import threading

import rclpy
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

import rclpy is unused in this module and will fail the repo's ament_flake8 check. Please remove it (or use it if needed).

Suggested change
import rclpy

Copilot uses AI. Check for mistakes.
Comment on lines +26 to +32
import re
import threading
import time

from rclpy.action import ActionServer, CancelResponse, GoalResponse
from rclpy.serialization import deserialize_message, serialize_message

Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

time is imported but unused in this module, which will fail ament_flake8 (F401). Please remove the unused import (or use it).

Copilot uses AI. Check for mistakes.
# Send the goal to the client using the __request / __response
# mechanism. send_unity_service_request blocks until the client
# responds. We use the action_name as the topic/destination
# so the client.s action server can route it.
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This comment has a typo: client.s should be client's.

Suggested change
# so the client.s action server can route it.
# so the client's action server can route it.

Copilot uses AI. Check for mistakes.
self.tcp_server.logerr(
"Action server '{}' not registered for feedback".format(action_name))
return
goal_uuid = bytes.fromhex(goal_uuid_hex)
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

_handle_action_feedback calls bytes.fromhex(goal_uuid_hex) without validation/exception handling. If the client sends a malformed UUID (wrong length, hyphens, etc.), this will raise ValueError and can terminate the TCP read loop. Please validate/normalize the UUID string and catch ValueError, logging an error and continuing.

Suggested change
goal_uuid = bytes.fromhex(goal_uuid_hex)
normalized_goal_uuid_hex = goal_uuid_hex.strip().replace("-", "")
if len(normalized_goal_uuid_hex) != 32:
self.tcp_server.logerr(
"Invalid goal UUID '{}' for action feedback '{}': expected 32 hex characters".format(
goal_uuid_hex, action_name))
return
try:
goal_uuid = bytes.fromhex(normalized_goal_uuid_hex)
except ValueError:
self.tcp_server.logerr(
"Invalid goal UUID '{}' for action feedback '{}': not valid hexadecimal".format(
goal_uuid_hex, action_name))
return

Copilot uses AI. Check for mistakes.
Comment on lines 70 to +79
self.node_name = node_name
self.publishers_table = {}
self.subscribers_table = {}
self.ros_services_table = {}
self.unity_services_table = {}
self.action_clients_table = {}
self.action_servers_table = {}
self.pending_action_op = None
self.pending_action_name = None
self.pending_action_goal_uuid = None
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You introduced action_clients_table / action_servers_table, but setup_executor() and destroy_nodes() still only consider publishers/subscribers/services. This means action nodes created before setup_executor() won't be added to the executor, and action nodes won't be destroyed on shutdown. Please update executor setup/cleanup to include these new tables (and consider including them in num_threads).

Copilot uses AI. Check for mistakes.
self.tcp_server.unregister_node(old_node)

new_client = RosActionClient(action_name, action_class,
self.tcp_server.unity_tcp_sender)
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

RosActionClient.__init__ takes a parameter named tcp_server, but you are passing self.tcp_server.unity_tcp_sender here. Even if it works today, this is easy to misread and will break if RosActionClient later needs the actual TcpServer. Please pass the TcpServer instance (or rename the constructor parameter to reflect what is expected).

Suggested change
self.tcp_server.unity_tcp_sender)
self.tcp_server)

Copilot uses AI. Check for mistakes.
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants