Skip to content

Commit

Permalink
action result now returns status
Browse files Browse the repository at this point in the history
  • Loading branch information
danmartzla committed Jan 6, 2025
1 parent bf42126 commit bcd403c
Show file tree
Hide file tree
Showing 4 changed files with 80 additions and 18 deletions.
71 changes: 55 additions & 16 deletions docs/files/ros2-action-client.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,30 +5,69 @@

global result

client = roslibpy.Ros(host="localhost", port=9090)
client.run()

action_client = roslibpy.ActionClient(client,
"/fibonacci",
"custom_action_interfaces/action/Fibonacci")
result = None

def result_callback(msg):
global result
result = msg["result"]
result = msg
print("Action result:", msg)

def feedback_callback(msg):
print(f"Action feedback: {msg['partial_sequence']}")

def fail_callback(msg):
print(f"Action failed: {msg}")

goal_id = action_client.send_goal(roslibpy.ActionGoal({"order": 8}),
result_callback,
feedback_callback,
fail_callback)

while result == None:
time.sleep(1)
def test_action_success(action_client):
""" This test function sends a action goal to an Action server.
"""
global result
result = None

print("Action result: {}".format(result["sequence"]))
action_client.send_goal(roslibpy.ActionGoal({"order": 8}),
result_callback,
feedback_callback,
fail_callback)

while result == None:
time.sleep(1)

print("-----------------------------------------------")
print("Action status:", result["status"])
print("Action result: {}".format(result["values"]["sequence"]))


def test_action_cancel(action_client):
""" This test function sends a cancel request to an Action server.
NOTE: Cancel request is not functional for now...
"""
global result
result = None

goal_id = action_client.send_goal(roslibpy.ActionGoal({"order": 8}),
result_callback,
feedback_callback,
fail_callback)
time.sleep(3)
print("Sending action goal cancel request...")
action_client.cancel_goal(goal_id)

while result == None:
time.sleep(1)

print("-----------------------------------------------")
print("Action status:", result["status"])
print("Action result: {}".format(result["values"]["sequence"]))


if __name__ == "__main__":
client = roslibpy.Ros(host="localhost", port=9090)
client.run()

action_client = roslibpy.ActionClient(client,
"/fibonacci",
"custom_action_interfaces/action/Fibonacci")
print("\n** Starting action client test **")
test_action_success(action_client)

print("\n** Starting action goal cancelation test **")
test_action_cancel(action_client)
2 changes: 2 additions & 0 deletions src/roslibpy/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -131,6 +131,7 @@ class and are passed around via :class:`Topics <Topic>` using a **publish/subscr
ActionClient,
ActionFeedback,
ActionGoal,
ActionGoalStatus,
ActionResult,
Header,
Message,
Expand Down Expand Up @@ -160,6 +161,7 @@ class and are passed around via :class:`Topics <Topic>` using a **publish/subscr
"ServiceResponse",
"ActionClient",
"ActionGoal",
"ActionGoalStatus",
"ActionFeedback",
"ActionResult",
"Time",
Expand Down
9 changes: 7 additions & 2 deletions src/roslibpy/comm/comm.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@

from roslibpy.core import (
ActionFeedback,
ActionGoalStatus,
ActionResult,
Message,
MessageEncoder,
Expand Down Expand Up @@ -162,9 +163,13 @@ def _handle_action_result(self, message):
resultback, _ , errback = action_handlers
del self._pending_action_requests[request_id]

LOGGER.debug("Received Action result with status: %s", message["status"])

results = {"status": ActionGoalStatus(message["status"]).name, "values": message["values"]}

if "result" in message and message["result"] is False:
if errback:
errback(message["values"])
errback(results)
else:
if resultback:
resultback(ActionResult(message["values"]))
resultback(ActionResult(results))
16 changes: 16 additions & 0 deletions src/roslibpy/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import json
import logging
import time
from enum import Enum

# Python 2/3 compatibility import list
try:
Expand Down Expand Up @@ -152,6 +153,20 @@ def __init__(self, values=None):
self.update(values)


class ActionGoalStatus(Enum):
""" ROS2 Action Goal statuses.
Reference: https://docs.ros2.org/latest/api/action_msgs/msg/GoalStatus.html
"""

UNKNOWN = 0
ACCEPTED = 1
EXECUTING = 2
CANCELING = 3
SUCCEEDED = 4
CANCELED = 5
ABORTED = 6


class ActionGoal(UserDict):
"""Action Goal for an action call."""

Expand Down Expand Up @@ -589,6 +604,7 @@ def cancel_goal(self, goal_id):
)
self.ros.send_on_ready(message)
# Remove message_id from RosBridgeProtocol._pending_action_requests in comms.py?
# Not needed since an action result is returned upon cancelation.


class Param(object):
Expand Down

0 comments on commit bcd403c

Please sign in to comment.