diff --git a/.github/workflows/build-ros1.yml b/.github/workflows/build-ros1.yml new file mode 100644 index 0000000..cb849a0 --- /dev/null +++ b/.github/workflows/build-ros1.yml @@ -0,0 +1,59 @@ +name: build + +on: + push: + branches: + - main + tags: + - 'v*' + pull_request: + branches: + - main + +jobs: + build-cpython: + runs-on: ${{ matrix.os }} + strategy: + matrix: + name: [ + "ubuntu-py39", + "ubuntu-py310", + "ubuntu-py311", + ] + include: + - name: "ubuntu-py39" + os: ubuntu-latest + python-version: "3.9" + - name: "ubuntu-py310" + os: ubuntu-latest + python-version: "3.10" + - name: "ubuntu-py311" + os: ubuntu-latest + python-version: "3.11" + steps: + - uses: actions/checkout@v3 + - name: Set up Python ${{ matrix.python-version }} + uses: actions/setup-python@v4 + with: + python-version: ${{ matrix.python-version }} + - name: Install dependencies + run: | + python -m pip install --upgrade pip + python -m pip install wheel + - name: Install + run: | + python -m pip install --no-cache-dir -r requirements-dev.txt + - name: Set up docker containers + run: | + docker build -t gramaziokohler/rosbridge:integration_tests_ros1 ./docker/ros1 + docker run -d -p 9090:9090 --name rosbridge gramaziokohler/rosbridge:integration_tests_ros1 /bin/bash -c "roslaunch /integration-tests.launch" + docker ps -a + - name: Run linter + run: | + invoke check + - name: Run tests + run: | + pytest tests/ros1 + - name: Tear down docker containers + run: | + docker rm -f rosbridge diff --git a/.github/workflows/build-ros2.yml b/.github/workflows/build-ros2.yml new file mode 100644 index 0000000..95aa6dd --- /dev/null +++ b/.github/workflows/build-ros2.yml @@ -0,0 +1,59 @@ +name: build + +on: + push: + branches: + - main + tags: + - 'v*' + pull_request: + branches: + - main + +jobs: + build-cpython: + runs-on: ${{ matrix.os }} + strategy: + matrix: + name: [ + "ubuntu-py39", + "ubuntu-py310", + "ubuntu-py311", + ] + include: + - name: "ubuntu-py39" + os: ubuntu-latest + python-version: "3.9" + - name: "ubuntu-py310" + os: ubuntu-latest + python-version: "3.10" + - name: "ubuntu-py311" + os: ubuntu-latest + python-version: "3.11" + steps: + - uses: actions/checkout@v3 + - name: Set up Python ${{ matrix.python-version }} + uses: actions/setup-python@v4 + with: + python-version: ${{ matrix.python-version }} + - name: Install dependencies + run: | + python -m pip install --upgrade pip + python -m pip install wheel + - name: Install + run: | + python -m pip install --no-cache-dir -r requirements-dev.txt + - name: Set up docker containers + run: | + docker build -t gramaziokohler/rosbridge:integration_tests_ros2 ./docker/ros2 + docker run -d -p 9090:9090 --name rosbridge gramaziokohler/rosbridge:integration_tests_ros2 /bin/bash -c "ros2 launch /integration-tests.launch" + docker ps -a + - name: Run linter + run: | + invoke check + - name: Run tests + run: | + pytest tests/ros2 + - name: Tear down docker containers + run: | + docker rm -f rosbridge diff --git a/docker/ros2/Dockerfile b/docker/ros2/Dockerfile index 5665ac5..b4a0148 100644 --- a/docker/ros2/Dockerfile +++ b/docker/ros2/Dockerfile @@ -6,9 +6,9 @@ SHELL ["/bin/bash","-c"] # Install rosbridge RUN apt-get update && apt-get install -y \ ros-iron-rosbridge-suite \ - ros-iron-tf2-web-republisher \ - ros-iron-ros-tutorials \ - ros-iron-actionlib-tutorials \ + # ros-iron-tf2-web-republisher \ + # ros-iron-ros-tutorials \ + # ros-iron-actionlib-tutorials \ --no-install-recommends \ # Clear apt-cache to reduce image size && rm -rf /var/lib/apt/lists/* diff --git a/docker/ros2/integration-tests.launch b/docker/ros2/integration-tests.launch index e28730b..1aedc6d 100644 --- a/docker/ros2/integration-tests.launch +++ b/docker/ros2/integration-tests.launch @@ -1,6 +1,4 @@ - - - + diff --git a/tests/test_actionlib.py b/tests/ros1/test_actionlib.py similarity index 100% rename from tests/test_actionlib.py rename to tests/ros1/test_actionlib.py diff --git a/tests/test_core.py b/tests/ros1/test_core.py similarity index 100% rename from tests/test_core.py rename to tests/ros1/test_core.py diff --git a/tests/test_param.py b/tests/ros1/test_param.py similarity index 100% rename from tests/test_param.py rename to tests/ros1/test_param.py diff --git a/tests/test_ros.py b/tests/ros1/test_ros.py similarity index 100% rename from tests/test_ros.py rename to tests/ros1/test_ros.py diff --git a/tests/test_rosapi.py b/tests/ros1/test_rosapi.py similarity index 100% rename from tests/test_rosapi.py rename to tests/ros1/test_rosapi.py diff --git a/tests/test_service.py b/tests/ros1/test_service.py similarity index 100% rename from tests/test_service.py rename to tests/ros1/test_service.py diff --git a/tests/test_tf.py b/tests/ros1/test_tf.py similarity index 100% rename from tests/test_tf.py rename to tests/ros1/test_tf.py diff --git a/tests/test_topic.py b/tests/ros1/test_topic.py similarity index 98% rename from tests/test_topic.py rename to tests/ros1/test_topic.py index 822edcb..74e04c8 100644 --- a/tests/test_topic.py +++ b/tests/ros1/test_topic.py @@ -68,7 +68,7 @@ def receive_message(message): context["wait"].set() def start_sending(): - for i in range(3): + for _ in range(3): msg = dict(header=Header(stamp=Time.now(), frame_id="base"), point=dict(x=0.0, y=1.0, z=2.0)) publisher.publish(Message(msg)) time.sleep(0.1) diff --git a/tests/ros2/test_topic_ros2.py b/tests/ros2/test_topic_ros2.py new file mode 100644 index 0000000..b899176 --- /dev/null +++ b/tests/ros2/test_topic_ros2.py @@ -0,0 +1,94 @@ +from __future__ import print_function + +import threading +import time + +from roslibpy import Message, Ros, Time, Topic +from roslibpy.ros2 import Header + + +def test_topic_pubsub(): + context = dict(wait=threading.Event(), counter=0) + + ros = Ros("127.0.0.1", 9090) + ros.run() + + listener = Topic(ros, "/chatter", "std_msgs/String") + publisher = Topic(ros, "/chatter", "std_msgs/String") + + def receive_message(message): + context["counter"] += 1 + assert message["data"] == "hello world", "Unexpected message content" + + if context["counter"] == 3: + listener.unsubscribe() + context["wait"].set() + + def start_sending(): + while True: + if context["counter"] >= 3: + break + publisher.publish(Message({"data": "hello world"})) + time.sleep(0.1) + publisher.unadvertise() + + def start_receiving(): + listener.subscribe(receive_message) + + t1 = threading.Thread(target=start_receiving) + t2 = threading.Thread(target=start_sending) + + t1.start() + t2.start() + + if not context["wait"].wait(10): + raise Exception + + t1.join() + t2.join() + + assert context["counter"] >= 3, "Expected at least 3 messages but got " + str(context["counter"]) + ros.close() + + +def test_topic_with_header(): + context = dict(wait=threading.Event()) + + ros = Ros("127.0.0.1", 9090) + ros.run() + + listener = Topic(ros, "/points", "geometry_msgs/PointStamped") + publisher = Topic(ros, "/points", "geometry_msgs/PointStamped") + + def receive_message(message): + assert message["header"]["frame_id"] == "base" + assert message["point"]["x"] == 0.0 + assert message["point"]["y"] == 1.0 + assert message["point"]["z"] == 2.0 + listener.unsubscribe() + context["wait"].set() + + def start_sending(): + for _ in range(3): + msg = dict(header=Header(stamp=Time.now(), frame_id="base"), point=dict(x=0.0, y=1.0, z=2.0)) + publisher.publish(Message(msg)) + time.sleep(0.1) + + publisher.unadvertise() + + def start_receiving(): + listener.subscribe(receive_message) + + t1 = threading.Thread(target=start_receiving) + t2 = threading.Thread(target=start_sending) + + t1.start() + t2.start() + + if not context["wait"].wait(10): + raise Exception + + t1.join() + t2.join() + + ros.close()