Skip to content

Commit

Permalink
Use unit test test cases
Browse files Browse the repository at this point in the history
Signed-off-by: Aaron Chong <aaronchongth@gmail.com>
  • Loading branch information
aaronchongth committed Nov 15, 2024
1 parent 4661bb2 commit 50677cc
Show file tree
Hide file tree
Showing 4 changed files with 44 additions and 56 deletions.
7 changes: 0 additions & 7 deletions .github/workflows/integration-tests.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -35,13 +35,6 @@ jobs:
if: always()
run: docker-compose -f ".github/docker/integration-tests/docker-compose.yaml" down

- name: Upload failed test results
uses: actions/upload-artifact@v4
if: failure()
with:
name: test-results
path: ros_ws/build/*/test_results/*/*.catch2.xml

- name: Upload coverage to Codecov
uses: codecov/codecov-action@v4
with:
Expand Down
16 changes: 0 additions & 16 deletions .github/workflows/unit-tests.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -22,19 +22,3 @@ jobs:
ros-distribution: ${{ matrix.ros_distribution }}
zenoh-version: 1.0.1
integration-testing: OFF

- name: Upload failed test results
uses: actions/upload-artifact@v4
if: failure()
with:
name: test-results
path: ros_ws/build/*/test_results/*/*.catch2.xml

- name: Upload coverage to Codecov
uses: codecov/codecov-action@v4
with:
files: ros_ws/coveragepy/.coverage
flags: tests
fail_ci_if_error: true
env:
CODECOV_TOKEN: ${{ secrets.CODECOV_TOKEN }}
42 changes: 23 additions & 19 deletions free_fleet_adapter/tests/integration/test_nav2_robot_adapter.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,20 +15,30 @@
# limitations under the License.

import time
import unittest

from free_fleet_adapter.nav2_robot_adapter import Nav2RobotAdapter
import rclpy
from rclpy.node import Node
from tf2_ros import Buffer

import zenoh


def test_robot_does_not_exist():
rclpy.init()
node = Node('missing_turtlebot3_1_nav2_robot_adapter_node')
zenoh.try_init_log_from_env()
with zenoh.open(zenoh.Config()) as session:
class TestNav2RobotAdapter(unittest.TestCase):

@classmethod
def setUpClass(cls):
rclpy.init()
cls.node = rclpy.create_node('test_nav2_robot_adapter')
cls.zenoh_session = zenoh.open(zenoh.Config())

@classmethod
def tearDownClass(cls):
cls.node.destroy_node()
cls.zenoh_session.close()
rclpy.shutdown()

def test_robot_does_not_exist(self):
tf_buffer = Buffer()

robot_adapter = Nav2RobotAdapter(
Expand All @@ -37,8 +47,8 @@ def test_robot_does_not_exist():
robot_config_yaml={
'initial_map': 'L1',
},
node=node,
zenoh_session=session,
node=self.node,
zenoh_session=self.zenoh_session,
fleet_handle=None,
tf_buffer=tf_buffer
)
Expand All @@ -53,12 +63,7 @@ def test_robot_does_not_exist():

assert not robot_exists


def test_robot_exists():
rclpy.init()
node = Node('turtlebot3_1_nav2_robot_adapter_node')
zenoh.try_init_log_from_env()
with zenoh.open(zenoh.Config()) as session:
def test_robot_exists(self):
tf_buffer = Buffer()

robot_adapter = Nav2RobotAdapter(
Expand All @@ -67,8 +72,8 @@ def test_robot_exists():
robot_config_yaml={
'initial_map': 'L1',
},
node=node,
zenoh_session=session,
node=self.node,
zenoh_session=self.zenoh_session,
fleet_handle=None,
tf_buffer=tf_buffer
)
Expand All @@ -81,8 +86,7 @@ def test_robot_exists():
break
time.sleep(1)

# To check that it is running
assert not robot_exists
assert robot_exists


# def test_robot_navigate():
# def test_robot_navigate():
35 changes: 21 additions & 14 deletions free_fleet_adapter/tests/integration/test_nav2_tf_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,24 +15,34 @@
# limitations under the License.

import time
import unittest

from free_fleet_adapter.nav2_robot_adapter import Nav2TfHandler
import rclpy
from rclpy.node import Node
from tf2_ros import Buffer

import zenoh


def test_tf_does_not_exist():
rclpy.init()
node = Node('missing_turtlebot3_1_node')
zenoh.try_init_log_from_env()
with zenoh.open(zenoh.Config()) as session:
class TestNav2TfHandler(unittest.TestCase):

@classmethod
def setUpClass(cls):
rclpy.init()
cls.node = rclpy.create_node('test_nav2_tf_handler')
cls.zenoh_session = zenoh.open(zenoh.Config())

@classmethod
def tearDownClass(cls):
cls.node.destroy_node()
cls.zenoh_session.close()
rclpy.shutdown()

def test_tf_does_not_exist(self):
tf_buffer = Buffer()

tf_handler = Nav2TfHandler(
'missing_turtlebot3_1', session, tf_buffer, node
'missing_turtlebot3_1', self.zenoh_session, tf_buffer, self.node
)

transform_exists = False
Expand All @@ -45,15 +55,12 @@ def test_tf_does_not_exist():

assert not transform_exists


def test_tf_exists():
rclpy.init()
node = Node('turtlebot3_1_node')
zenoh.try_init_log_from_env()
with zenoh.open(zenoh.Config()) as session:
def test_tf_exists(self):
tf_buffer = Buffer()

tf_handler = Nav2TfHandler('turtlebot3_1', session, tf_buffer, node)
tf_handler = Nav2TfHandler(
'turtlebot3_1', self.zenoh_session, tf_buffer, self.node
)

transform_exists = False
for i in range(10):
Expand Down

0 comments on commit 50677cc

Please sign in to comment.