Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add docs & tests for actions #39

Merged
merged 2 commits into from
May 13, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 5 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -82,10 +82,12 @@ Using `ROS2TestEnvironment`, you can call:
- `publish(topic: str, message: RosMessage) -> None`
- `listen_for_messages(topic: str, time_span: float) -> List[RosMessage]`
- `clear_messages(topic: str) -> None` to forget all messages that have been received so far.
- `call_service(name: str, request: Request, timeout_availability: Optional[float], timeout_call: Optional[float]) -> Response`
- `call_service(name: str, request: Request, ...) -> Response`
- `send_action_goal(name: str, goal: Any, ...) -> Tuple[ClientGoalHandle, List[FeedbackMsg]]`
- `send_action_goal_and_wait_for_result(name: str, goal: Any, ...) -> Tuple[List[FeedbackMsg], ResultMsg]`

Note that `ROS2TestEnvironment` is a [`rclpy.node.Node`](https://docs.ros2.org/latest/api/rclpy/api/node.html) and thus has all the methods of a ROS2 node.
So feel free to call offer a service with `env.create_service()`, interface with an action using `ActionClient(env, DoTheThing, 'maker')`, etc., to cover more specific use cases.
Note that a `ROS2TestEnvironment` is a normal [`rclpy.node.Node`](https://docs.ros2.org/latest/api/rclpy/api/node.html) and thus has all the methods of any other ROS2 node.
So feel free to offer a service with `env.create_service()` and cover more specific use cases.
Extend as you please!

In addition, nothing stops you from using any other means of interacting with ROS2 that would work otherwise.
Expand Down
4 changes: 2 additions & 2 deletions ros2_easy_test/ros2_easy_test/env.py
Original file line number Diff line number Diff line change
Expand Up @@ -492,10 +492,10 @@ def send_action_goal_and_wait_for_result(
result = self.await_future(goal_handle.get_result_async(), timeout=timeout_get_result)

# Make sure the goal was reached successfully
assert goal_handle.status == GoalStatus.STATUS_SUCCEEDED
assert result.status == GoalStatus.STATUS_SUCCEEDED, f"Goal did not succeed: {result.status=}"

# Return the results to the test case
return feedbacks, result
return feedbacks, result.result

def destroy_node(self):
# Actions don't get destroyed automatically
Expand Down
10 changes: 8 additions & 2 deletions ros2_easy_test/tests/example_nodes/minimal_action_server.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
# Modified from original example in examples_rclpy_minimal_action_server.server as follows:
# 1. pass *args, **kwargs to __init__ and super().__init__.
# 2. Reduce sleep times.
# 3. Reject goal requests with order < 0.
# 4. Cleanup/modernization.
#
# Copyright 2019 Open Source Robotics Foundation, Inc.
#
Expand Down Expand Up @@ -45,8 +47,12 @@ def destroy(self):
def goal_callback(self, goal_request):
"""Accept or reject a client request to begin an action."""
# This server allows multiple goals in parallel
self.get_logger().info("Received goal request")
return GoalResponse.ACCEPT
if goal_request.order < 0:
self.get_logger().info("Rejecting goal request")
return GoalResponse.REJECT
else:
self.get_logger().info("Accepting goal request")
return GoalResponse.ACCEPT

def cancel_callback(self, goal_handle):
"""Accept or reject a client request to cancel an action."""
Expand Down
47 changes: 0 additions & 47 deletions ros2_easy_test/tests/test_actions.py

This file was deleted.

56 changes: 56 additions & 0 deletions ros2_easy_test/tests/test_env_coverage.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
from unittest import TestCase

# Testing
from action_msgs.srv import CancelGoal
from example_interfaces.action import Fibonacci
from pytest import mark
from std_msgs.msg import Empty, String

Expand All @@ -14,6 +16,7 @@
from . import LAUNCH_FILES

# Module under test and interfaces
from .example_nodes.minimal_action_server import MinimalActionServer
from .example_nodes.well_behaved import EchoNode, Talker


Expand Down Expand Up @@ -97,6 +100,59 @@ def test_mailbox_clearing_no_topics(self, env: ROS2TestEnvironment) -> None:
def test_wrong_topic_type(self, env: ROS2TestEnvironment) -> None:
pass

@mark.xfail(
raises=Exception,
reason="specifiying a wrong/nonexistent action server name a common mistake and shall fail loudly",
strict=True,
)
@with_single_node(MinimalActionServer)
def test_calling_nonexistent_action(self, env: ROS2TestEnvironment) -> None:
# The following isn't even an action at all, but these are no other actions easily available
env.send_action_goal("/does_no_exist", String("Hello World"))

@mark.xfail(
raises=TimeoutError,
reason="specifiying a wrong action message type is a common mistake and shall fail loudly",
strict=True,
)
@with_single_node(MinimalActionServer)
def test_calling_action_wrong_type(self, env: ROS2TestEnvironment) -> None:
env.send_action_goal("/does_no_exist", Fibonacci.Goal(order=1), timeout_availability=0.1)

@mark.xfail(
raises=AssertionError,
reason="rejections should be recognized as such",
strict=True,
)
@with_single_node(MinimalActionServer)
def test_action_rejection(self, env: ROS2TestEnvironment) -> None:
env.send_action_goal_and_wait_for_result("fibonacci", Fibonacci.Goal(order=-3))

@with_single_node(MinimalActionServer)
def test_cancelling_an_action(self, env: ROS2TestEnvironment) -> None:
goal_handle, _ = env.send_action_goal("fibonacci", Fibonacci.Goal(order=10))

cancel_response: CancelGoal.Response = goal_handle.cancel_goal()
assert cancel_response.return_code in {
CancelGoal.Response.ERROR_NONE,
CancelGoal.Response.ERROR_GOAL_TERMINATED,
}

@with_single_node(MinimalActionServer)
def test_concurrent_actions(self, env: ROS2TestEnvironment) -> None:
# (1) Call async
goal_handle1, _ = env.send_action_goal("fibonacci", Fibonacci.Goal(order=10))

# (2) Call sync
_, result2 = env.send_action_goal_and_wait_for_result("fibonacci", Fibonacci.Goal(order=1))

# Check result of (1)
result1 = goal_handle1.get_result().result
assert result1 == Fibonacci.Result(sequence=[0, 1, 1, 2, 3, 5, 8, 13, 21, 34, 55])

# Check result of (2)
assert result2 == Fibonacci.Result(sequence=[0, 1])


if __name__ == "__main__":
unittest.main()
31 changes: 31 additions & 0 deletions ros2_easy_test/tests/test_interactions.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
from unittest import TestCase

# Other ROS2 interfaces
from example_interfaces.action import Fibonacci
from example_interfaces.srv import AddTwoInts

# Testing
Expand All @@ -20,6 +21,7 @@
from . import LAUNCH_FILES

# Module under test and interfaces
from .example_nodes.minimal_action_server import MinimalActionServer
from .example_nodes.well_behaved import AddTwoIntsServer, EchoNode, Talker


Expand Down Expand Up @@ -95,6 +97,27 @@ def test_multiple_messages(self, env: ROS2TestEnvironment, count: int = 5) -> No
expected = [String(data=f"Hi #{identifier}") for identifier in range(count)]
self.assertListEqual(all_messages, expected)

def test_calling_an_action(self, env: ROS2TestEnvironment) -> None:
feedbacks, result = env.send_action_goal_and_wait_for_result(
name="fibonacci", goal=Fibonacci.Goal(order=4)
)

assert len(feedbacks) == 3
assert feedbacks == [
Fibonacci.Feedback(sequence=[0, 1, 1]),
Fibonacci.Feedback(sequence=[0, 1, 1, 2]),
Fibonacci.Feedback(sequence=[0, 1, 1, 2, 3]),
]

assert result == Fibonacci.Result(sequence=[0, 1, 1, 2, 3])

# We call it again to test if resources are reused properly
feedbacks2, result2 = env.send_action_goal_and_wait_for_result(
name="fibonacci", goal=Fibonacci.Goal(order=3)
)
assert feedbacks2 == feedbacks[:2]
assert result2 == Fibonacci.Result(sequence=[0, 1, 1, 2])


class TestSingleNode(SharedTestCases, TestCase):
"""This test case uses the ``with_single_node`` decorator to set up the test environment."""
Expand Down Expand Up @@ -137,6 +160,10 @@ def test_multiple_messages_stress_test(self, env: ROS2TestEnvironment) -> None:
def test_assertion_raised(self, env: ROS2TestEnvironment) -> None:
self.fail("This should fail the test case")

@with_single_node(MinimalActionServer)
def test_calling_an_action(self, env: ROS2TestEnvironment) -> None:
super().test_calling_an_action(env)


class TestLaunchFile(SharedTestCases, TestCase):
"""This test case uses the ``with_launch_file`` decorator to set up the test environment."""
Expand Down Expand Up @@ -195,6 +222,10 @@ def test_multiple_messages_stress_test(self, env: ROS2TestEnvironment) -> None:
def test_assertion_raised(self, env: ROS2TestEnvironment) -> None:
self.fail("This should fail the test case")

@with_launch_file(LAUNCH_FILES / "fibonacci_action.yaml")
def test_calling_an_action(self, env: ROS2TestEnvironment) -> None:
super().test_calling_an_action(env)


if __name__ == "__main__":
unittest.main()
Loading