diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 4128f9a9518c7cad63788a87508fdcfdb804d605..ff45a6dc2a8717ec4700d409c23e80b85174cb5a 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -109,6 +109,38 @@ pypi-scripted-tdma run_tests: TEST_DYNAMIC_QUEUES: "true" TDMA_TYPE: "tdma_scripted" +test-with-hardware: + stage: test + tags: + - modembox + image: ros_acomms-tests:latest + script: + - source /ros_entrypoint.sh + - mkdir -p ~/catkin_ws/src + - cd ../ && cp -r $CI_PROJECT_NAME ~/catkin_ws/src/ + - cd ~/catkin_ws/src/ros_acomms && pip install -U -r requirements.txt + - cd ~/catkin_ws && catkin_make + - roscore & + - sleep 5 + - source devel/setup.bash + - TESTS_PATH=$(rospack find ros_acomms_tests)/src + - ROS_ACOMMS_PATH=$(rospack find ros_acomms)/src + - ROS_ACOMMS_MODELING_PATH=$(rospack find ros_acomms_modeling)/src + - cd ${CI_PROJECT_DIR} + - socat /dev/ttyUSB1,b19200,raw,echo=0 udp-listen:4002,fork | socat - udp:localhost:4001 & + - pytest --capture=no --junitxml=test_with_hardware.results.xml --cov=$ROS_ACOMMS_PATH --cov-report= $TESTS_PATH/test_with_hardware.py + - mv .coverage test_with_hardware.coverage # Note that the next call to pytest will delete anything that starts with .coverage* + - coverage combine --keep *.coverage + - coverage report + - mv .coverage "$CI_JOB_NAME_SLUG.job.coverage" + except: + - dev/autodocs + artifacts: + paths: + - '*.coverage' + reports: + junit: '*.results.xml' + test-coverage: image: ros_acomms-tests:latest except: @@ -118,6 +150,7 @@ test-coverage: - "pypi-basic-tdma run_tests" - "pypi-advanced-tdma run_tests" - "pypi-scripted-tdma run_tests" + - "test-with-hardware" script: - mkdir -p ~/catkin_ws/src - cp -r ../$CI_PROJECT_NAME ~/catkin_ws/src/ diff --git a/ros_acomms/src/acomms_codecs/ccl_packet_codec.py b/ros_acomms/src/acomms_codecs/ccl_packet_codec.py index e32ca3af52041c91e49f32b9021b9cf22ae5c1de..be8c52f875f4f749955ae51645d17f629d4ac55a 100644 --- a/ros_acomms/src/acomms_codecs/ccl_packet_codec.py +++ b/ros_acomms/src/acomms_codecs/ccl_packet_codec.py @@ -24,7 +24,7 @@ class PacketCodec(BasePacketCodec): # Add headers. CCL messages can't have additional headers on the frame, but we can (theoretically) use # miniframe headers in conjunction with the "print_rxd" option on TFP messages. - miniframe_bits = BitArray(bytes=self.miniframe_header) + miniframe_bits = BitArray(bytes=bytes(self.miniframe_header)) remaining_miniframe_bits -= miniframe_bits.length dataframe_bits = BitArray() diff --git a/ros_acomms/src/acomms_codecs/ros_packet_codec.py b/ros_acomms/src/acomms_codecs/ros_packet_codec.py index e705f44bb21a03206028a8e632688f5e539a2178..adfb3cd7660724154ff939b81d0ed0a1fab02229 100644 --- a/ros_acomms/src/acomms_codecs/ros_packet_codec.py +++ b/ros_acomms/src/acomms_codecs/ros_packet_codec.py @@ -61,9 +61,9 @@ class PacketCodec(BasePacketCodec): remaining_dataframe_bits = num_dataframe_bytes * 8 # Add headers - miniframe_bits = BitArray(bytes=self.miniframe_header) + miniframe_bits = BitArray(bytes=bytes(self.miniframe_header)) remaining_miniframe_bits = max(remaining_miniframe_bits - miniframe_bits.length, 0) - dataframe_bits = BitArray(bytes=self.dataframe_header) + dataframe_bits = BitArray(bytes=bytes(self.dataframe_header)) remaining_dataframe_bits = max(remaining_dataframe_bits - dataframe_bits.length, 0) total_remaining_bits = remaining_miniframe_bits + remaining_dataframe_bits diff --git a/ros_acomms/src/acomms_driver_node.py b/ros_acomms/src/acomms_driver_node.py index b297dbb22f5381e8eb9c21622743d3ed5942dd80..86d5556bf0db30e22643efd2873d3900835eb559 100755 --- a/ros_acomms/src/acomms_driver_node.py +++ b/ros_acomms/src/acomms_driver_node.py @@ -171,7 +171,11 @@ class AcommsDriverNode(object): rospy.loginfo("Got modem SRC: {}".format(self.um.id)) rospy.set_param("modem_src", int(self.um.id)) # make relative to namespace, for other nodes to use - self.tat_ms = float(self.um.get_config("TAT", response_timeout=2)["TAT"]) + try: + self.tat_ms = float(self.um.get_config("TAT", response_timeout=2)["TAT"]) + except TypeError as e: + rospy.logwarn("Unable to get modem TAT. Setting to 0, which probably won't work") + self.tat_ms = 0 # Hack to work around 7-bit/8-bit addressing problems with legacy packets. self.um._ignore_cacyc_address_mismatch = True diff --git a/ros_acomms/src/message_queue_node.py b/ros_acomms/src/message_queue_node.py index 5026939022fe501635e84061e8d777d60a7ffae3..521a108fdd8f1c1086a3935becfdf68c970e3c1d 100755 --- a/ros_acomms/src/message_queue_node.py +++ b/ros_acomms/src/message_queue_node.py @@ -1,6 +1,7 @@ #!/usr/bin/env python3 from __future__ import unicode_literals, annotations +import traceback from itertools import groupby from typing import Any, Deque, Dict, List, Optional, Tuple, Union @@ -799,7 +800,8 @@ class MessageQueueNode(object): self.mark_transmitted(msg) except Exception as e: # If anything goes wrong, we still want to release the lock - rospy.logerr(f"Exception in get_next_packet_data: {e}") + traceback_str = traceback.format_exc() + rospy.logerr(f"Exception in get_next_packet_data: {e}\nTraceback:\n{traceback_str}") self.get_packet_data_lock.release() return GetNextPacketDataResponse() else: diff --git a/ros_acomms_tests/launch/test_with_hardware.launch b/ros_acomms_tests/launch/test_with_hardware.launch new file mode 100644 index 0000000000000000000000000000000000000000..61009e781adf42f182dfce0cc893e43e3a3cf876 --- /dev/null +++ b/ros_acomms_tests/launch/test_with_hardware.launch @@ -0,0 +1,76 @@ +<launch> + <env name="ROSCONSOLE_FORMAT" value="[${severity}] [${time}] [${node}]: ${message}"/> + + <group ns="modem0"> + <node name="acomms_driver_node" pkg="ros_acomms" type="acomms_driver_node.py" output="screen" > + <param name="modem_connection_type" value="serial" /> + <param name="modem_serial_port" value="/dev/ttyUSB0" type="str" /> + <param name="modem_baud_rate" value="19200" type="int" /> + <param name="pwramp_txlevel" value="3" type="int" /> + <rosparam param="modem_config"> + ALL: 0 + SRC: 0 + BND: 0 + FC0: 10000 + BW0: 5000 + pwramp.txlevel: 3 + psk.packet.mod_hdr_version: 1 + </rosparam> + </node> + + <node name="tdma" pkg="ros_acomms" type="tdma_node.py" output="screen" required="true" respawn="false"> + <param name="num_slots" value="2"/> + <param name="active_slots" value="0"/> + <param name="slot_duration_seconds" value="10" /> + <param name="guard_time_seconds" value="3" /> + </node> + + + <node name="message_queue_node" pkg="ros_acomms" type="message_queue_node.py" output="screen" > + <param name="packet_codec_file" value="$(find ros_acomms_tests)/launch/message_codec_config.yaml"/> + </node> + + <node name="packet_dispatch" pkg="ros_acomms" type="packet_dispatch_node.py" output="screen" > + <param name="packet_codec_file" value="$(find ros_acomms_tests)/launch/message_codec_config.yaml"/> + </node> + + <node name="modem_sensor_data" pkg="ros_acomms" type="modem_sensor_data_node.py" output="screen"> + <param name="query_interval_seconds" value="10"/> + </node> + </group> + + <group ns="modem1"> + <node name="acomms_driver_node" pkg="ros_acomms" type="acomms_driver_node.py" output="screen" > + <param name="modem_connection_type" value="udp" /> + <param name="modem_local_port" value="4001" /> + <param name="modem_remote_port" value="4002" /> + <param name="pwramp_txlevel" value="3" type="int" /> + <rosparam param="modem_config"> + ALL: 0 + SRC: 1 + BND: 0 + FC0: 10000 + BW0: 5000 + pwramp.txlevel: 3 + psk.packet.mod_hdr_version: 1 + </rosparam> + </node> + + <node name="tdma_advanced" pkg="ros_acomms" type="tdma_node.py" output="screen" required="true" respawn="false"> + <param name="num_slots" value="2"/> + <param name="active_slots" value="1"/> + <param name="slot_duration_seconds" value="10" /> + <param name="guard_time_seconds" value="3" /> + </node> + + <node name="message_queue_node" pkg="ros_acomms" type="message_queue_node.py" output="screen" > + <param name="packet_codec_file" value="$(find ros_acomms_tests)/launch/message_codec_config.yaml"/> + </node> + + <node name="packet_dispatch" pkg="ros_acomms" type="packet_dispatch_node.py" output="screen" > + <param name="packet_codec_file" value="$(find ros_acomms_tests)/launch/message_codec_config.yaml"/> + </node> + + </group> + +</launch> diff --git a/ros_acomms_tests/src/test_with_hardware.py b/ros_acomms_tests/src/test_with_hardware.py new file mode 100644 index 0000000000000000000000000000000000000000..5afe41b6e11792b91feb6bf96858428249a8617b --- /dev/null +++ b/ros_acomms_tests/src/test_with_hardware.py @@ -0,0 +1,104 @@ +#! /usr/bin/env python3 + +''' +tests for ros_acomms +''' +import hashlib +import os +import secrets +import sys +import time +import traceback + +import pytest +import rospy +import rospkg +import roslaunch + +from std_msgs.msg import UInt8 + + +class TestRosAcommsSerial: + '''ros_acomms test class''' + + @classmethod + def setup_class(self): + """ + setup function for tests + """ + self.test_counter = 0 + rospy.init_node("ros_acomms_test_serial", log_level=rospy.INFO) + + self.rospack = rospkg.RosPack() + + uuid = roslaunch.rlutil.get_or_generate_uuid(None, False) + roslaunch.configure_logging(uuid) + + launch_file = os.path.join( + self.rospack.get_path("ros_acomms_tests"), + "launch/test_with_hardware.launch", + ) + + roslaunch_args = [] + full_cmd_list = [launch_file] + roslaunch_args + roslaunch_file_param = [(roslaunch.rlutil.resolve_launch_arguments(full_cmd_list)[0], roslaunch_args)] + + self.launch = roslaunch.parent.ROSLaunchParent(uuid, roslaunch_file_param) + self.launch.start() + time.sleep(5) + + def test_queue(self): + '''test_queue sends 3 messages through the ros_acomms and verifies that all 3 of the messages are recieved''' + + queue_publisher = rospy.Publisher('/modem0/test_msg', UInt8, queue_size=5) + + return_arr = [] + input_arr = [] + + msg = UInt8() + + print("Waiting for modem drivers...") + + # Wait until the modem drivers are ready + try: + rospy.wait_for_service('/modem0/queue_tx_packet', timeout=30) + rospy.wait_for_service('/modem1/queue_tx_packet', timeout=30) + except rospy.exceptions.ROSException: + pytest.fail("Timed out waiting for modem drivers to be ready") + + print("Modem drivers ready.") + + use_sim_time = rospy.get_param("/use_sim_time", None) + if use_sim_time is not None: + pytest.fail("Sim time is active, it should be off for the hardware test.") + + time.sleep(2) + + try: + for val in range(3): + msg.data = val + queue_publisher.publish(msg) + print(f"Published test message {val}") + + ret = rospy.wait_for_message( + "/modem1/from_acomms/test_msg", UInt8, timeout=60) + + return_arr.append(ret.data) + input_arr.append(msg.data) + + assert return_arr == input_arr, f"return_arr: {return_arr} != input_arr: {input_arr}" + + except rospy.exceptions.ROSException: + pytest.fail("timed out when waiting for packet") + + @classmethod + def teardown_class(self): + """ + teardown function for tests + """ + + self.launch.shutdown() + + +if __name__ == "__main__": + sys.exit(pytest.main(['--capture=no', __file__])) diff --git a/ros_acomms_tests/tests.Dockerfile b/ros_acomms_tests/tests.Dockerfile index 6d94cb3bd4c27dc9351aec913a047a78e60d9355..ca67210dc10be86a93663214e186d36e464918f8 100644 --- a/ros_acomms_tests/tests.Dockerfile +++ b/ros_acomms_tests/tests.Dockerfile @@ -5,5 +5,6 @@ RUN apt-get update \ && apt install -y \ python3-pip \ git \ - ros-noetic-dynamic-reconfigure + ros-noetic-dynamic-reconfigure \ + socat RUN pip install pytest pytest-cov \ No newline at end of file