Skip to content
Closed
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
3 changes: 2 additions & 1 deletion docker/ros2/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@ RUN apt-get update && apt-get install -y \
ros-${ROS_DISTRO}-rosbridge-suite \
# ros-${ROS_DISTRO}-tf2-web-republisher \
# ros-${ROS_DISTRO}-ros-tutorials \
# ros-${ROS_DISTRO}-actionlib-tutorials \
ros-${ROS_DISTRO}-examples-rclpy-minimal-action-server \
ros-${ROS_DISTRO}-example-interfaces \
--no-install-recommends \
# Clear apt-cache to reduce image size
&& rm -rf /var/lib/apt/lists/*
Expand Down
7 changes: 5 additions & 2 deletions docker/ros2/integration-tests.launch
Original file line number Diff line number Diff line change
@@ -1,4 +1,7 @@
<launch>
<include file="$(find-pkg-share rosbridge_server)/launch/rosbridge_websocket_launch.xml" />
<!-- <node pkg="tf2_web_republisher" type="tf2_web_republisher" name="tf2_web_republisher"></node> -->
<include file="$(find-pkg-share rosbridge_server)/launch/rosbridge_websocket_launch.xml">
<let name="send_action_goals_in_new_thread" value="true"/>
</include>
<!-- <node pkg="tf2_web_republisher" type="tf2_web_republisher" name="tf2_web_republisher"></node> -->
<node pkg="examples_rclpy_minimal_action_server" exec="server"/>
</launch>
67 changes: 67 additions & 0 deletions tests/ros2/test_actions_client.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
from __future__ import print_function

import time

import pytest

from roslibpy import Ros, ActionGoal
from roslibpy.actionlib import ActionClient

# @pytest.fixture
# def action_client():
# ros = Ros(host="localhost", port=9090)
# ros.run()

# return ActionClient(
# ros,
# "/fibonacci",
# "custom_action_interfaces/action/Fibonacci"
# )


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


def test_action_success():

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

action_client = ActionClient(ros, "/fibonacci", "example_interfaces/action/Fibonacci")

result = None

def result_feedback(msg):
result = msg

action_client.send_goal(ActionGoal({"order": 8}), result_feedback, feedback_callback)

while result is None:
time.sleep(1)

assert result["status"] == "success"
assert result["values"]["sequence"][-1] == 21


def test_action_cancellation():

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

action_client = ActionClient(ros, "/fibonacci", "example_interfaces/action/Fibonacci")

result = None

goal_id = action_client.send_goal(
ActionGoal({"order": 8}), None, feedback_callback, lambda msg: print(f"Action failed with message: {msg}")
)
time.sleep(3)
print("Sending action goal cancel request...")
action_client.cancel_goal(goal_id)

while result is None:
time.sleep(1)

assert result["status"] == "cancelled"
assert result["values"]
Loading