Skip to content

Commit

Permalink
Tools: clean up test case [skip ci]
Browse files Browse the repository at this point in the history
Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring committed Apr 11, 2023
1 parent c4450a6 commit 972a926
Show file tree
Hide file tree
Showing 2 changed files with 48 additions and 108 deletions.
43 changes: 43 additions & 0 deletions Tools/ros2/ardupilot_dds_tests/test/param_loader_wip.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
"""
A parameter loader for test cases (WIP)
"""

# class DDSParams(object):
# def __init__(self):
# super().__init__()
#
# # default params
# self.mra_serial_device = f"./dev/ttyROS0"
# self.mra_serial_baud = 115200
# self.mra_refs_file = "dds_xrce_profile.xml"
#
# self.ap_sim_vehicle_cmd = "sim_vehicle.py"
# self.ap_serial_device = f"./dev/ttyROS1"
# self.ap_serial_baud = 115200
# self.ap_vehicle = "ArduCopter"
# self.ap_frame = "quad"
#
# pkg = get_package_share_directory("ardupilot_dds_tests")
#
# # The micro_ros_agent and ardupilot nodes do not expose params
# # as ROS params, parse the config file and send them in as node args.
# params = os.path.join(pkg, "config", "ardupilot_dds.yaml")
#
# with open(params, "r") as f:
# params_str = f.read()
# params = yaml.safe_load(params_str)
# print(params)
#
# mra_params = params["/micro_ros_agent"]
# if mra_params["transport"] == "serial":
# self.mra_serial_baud = f"{mra_params['serial_baud']}"
# self.mra_serial_device = f"{mra_params['serial_device']}"
# self.mra_refs_file = f"{mra_params['refs_file']}"
#
# ap_params = params["/ardupilot"]
# if ap_params:
# self.ap_sim_vehicle_cmd = ap_params["sim_vehicle_cmd"]
# self.ap_vehicle = ap_params["vehicle"]
# self.ap_frame = ap_params["frame"]
# self.ap_serial_device = ap_params["serial_device"]
# self.ap_serial_baud = ap_params["serial_baud"]
113 changes: 5 additions & 108 deletions Tools/ros2/ardupilot_dds_tests/test/test_time_msg_received.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,83 +6,21 @@
import os
import pytest
import rclpy
# import time

import rclpy.node
import threading
# import Event
# from threading import Thread

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
# from launch.actions import EmitEvent
# from launch.actions import ExecuteProcess
from launch.actions import IncludeLaunchDescription
# from launch.actions import LogInfo
# from launch.actions import RegisterEventHandler
# from launch.actions import TimerAction
# from launch.event_handlers import OnProcessStart
# from launch.event_handlers import OnProcessExit
# from launch.events import matches_action
# from launch.events import Shutdown
# from launch.events.process import ShutdownProcess
from launch.launch_description_sources import PythonLaunchDescriptionSource
# from launch.substitutions import FindExecutable
from launch.substitutions import PathJoinSubstitution

# from launch_pytest.tools import process as process_tools

from launch_ros.substitutions import FindPackageShare

from builtin_interfaces.msg import Time


# class DDSParams(object):
# def __init__(self):
# super().__init__()
#
# # default params
# self.mra_serial_device = f"./dev/ttyROS0"
# self.mra_serial_baud = 115200
# self.mra_refs_file = "dds_xrce_profile.xml"
#
# self.ap_sim_vehicle_cmd = "sim_vehicle.py"
# self.ap_serial_device = f"./dev/ttyROS1"
# self.ap_serial_baud = 115200
# self.ap_vehicle = "ArduCopter"
# self.ap_frame = "quad"
#
# pkg = get_package_share_directory("ardupilot_dds_tests")
#
# # The micro_ros_agent and ardupilot nodes do not expose params
# # as ROS params, parse the config file and send them in as node args.
# params = os.path.join(pkg, "config", "ardupilot_dds.yaml")
#
# with open(params, "r") as f:
# params_str = f.read()
# params = yaml.safe_load(params_str)
# print(params)
#
# mra_params = params["/micro_ros_agent"]
# if mra_params["transport"] == "serial":
# self.mra_serial_baud = f"{mra_params['serial_baud']}"
# self.mra_serial_device = f"{mra_params['serial_device']}"
# self.mra_refs_file = f"{mra_params['refs_file']}"
#
# ap_params = params["/ardupilot"]
# if ap_params:
# self.ap_sim_vehicle_cmd = ap_params["sim_vehicle_cmd"]
# self.ap_vehicle = ap_params["vehicle"]
# self.ap_frame = ap_params["frame"]
# self.ap_serial_device = ap_params["serial_device"]
# self.ap_serial_baud = ap_params["serial_baud"]

# @pytest.fixture(scope="module")
# def dds_params():
# params = DDSParams()
# return params


@pytest.fixture(scope="module")
def device_dir(tmp_path_factory):
"""
Expand All @@ -92,18 +30,6 @@ def device_dir(tmp_path_factory):
return path


# @pytest.fixture()
# def dummy_proc():
# """
# A dummy process to manage test test lifetime.
# """
# return ExecuteProcess(
# cmd=["echo", "ardupilot_dds_tests"],
# shell=True,
# cached_output=True,
# )


@pytest.fixture
def bringup_sitl_dds(device_dir):
"""
Expand Down Expand Up @@ -205,41 +131,12 @@ def bringup_sitl_dds(device_dir):


@launch_pytest.fixture
def launch_description(dummy_proc, bringup_sitl_dds):
def launch_description(bringup_sitl_dds):
"""
Launch test fixture to create the launch description.
"""
# on_start = RegisterEventHandler(
# event_handler=OnProcessStart(
# target_action=dummy_proc,
# on_start=[
# LogInfo(msg="Test started."),
# # TimerAction(
# # period=10.0,
# # actions=[
# # LogInfo(msg="Test stopped."),
# # ],
# # ),
# ],
# )
# )

# on_process_exit = RegisterEventHandler(
# event_handler=OnProcessExit(
# target_action=dummy_proc,
# on_exit=[
# LogInfo(msg="Test stopping."),
# # EmitEvent(event=ShutdownProcess(
# # process_matcher=matches_action(bringup_sitl_dds))),
# ]
# )
# )

return LaunchDescription([
# dummy_proc,
bringup_sitl_dds,
# on_start,
# on_process_exit,
launch_pytest.actions.ReadyToTest(),
])

Expand Down Expand Up @@ -282,7 +179,7 @@ def subscriber_callback(self, msg):


@pytest.mark.launch(fixture=launch_description)
def test_time_msgs_received(dummy_proc, bringup_sitl_dds, launch_context):
def test_time_msgs_received(bringup_sitl_dds, launch_context):
"""
Test case for time messages published by AP_DDS.
"""
Expand All @@ -297,5 +194,5 @@ def test_time_msgs_received(dummy_proc, bringup_sitl_dds, launch_context):

yield

# this is executed after launch service shutdown
assert dummy_proc.return_code == 0
# anything below this line is executed after launch service shutdown.
pass

0 comments on commit 972a926

Please sign in to comment.