From ed53afac75bc062e20d286aed6e0b0888d09af91 Mon Sep 17 00:00:00 2001 From: caileighf <caileighfitzgerald@gmail.com> Date: Thu, 11 May 2023 02:50:35 +0000 Subject: [PATCH 1/4] first go at tdma test mac. Tested in sim. This test mac layer inherits from tdma_node.py (TdmaMacNode) and adds the ability to cycle through rates and max bytes (mini/data-frame) defined in a yaml. You can also specify a "test/settings" transmit count, i.e., define the number of TXs (actually just # of times it checks to message queue while active, but in practice there is always a message in the queue, this will cycle through tests if there is nothing in the queue, same as if there was) before moving on to the next defined test in the yaml. TODO, add ability to leave maximum_Tframe_bytes empty in yaml and use rates default (now supported in the tdma super class) --- CMakeLists.txt | 1 + launch/modem_sim_tdma_test_mac.launch | 75 +++++++++++++ launch/tdma_test_plan.yaml | 18 ++++ msg/TdmaTestMacStatus.msg | 14 +++ src/tdma_test_mac_node.py | 146 ++++++++++++++++++++++++++ 5 files changed, 254 insertions(+) create mode 100644 launch/modem_sim_tdma_test_mac.launch create mode 100644 launch/tdma_test_plan.yaml create mode 100644 msg/TdmaTestMacStatus.msg create mode 100755 src/tdma_test_mac_node.py diff --git a/CMakeLists.txt b/CMakeLists.txt index b4df0c03..5401e4f0 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -73,6 +73,7 @@ add_message_files(FILES SummaryMessageCount.msg TdmaStatus.msg TdmaNavStatus.msg + TdmaTestMacStatus.msg Tick.msg Tock.msg TransmittedPacket.msg diff --git a/launch/modem_sim_tdma_test_mac.launch b/launch/modem_sim_tdma_test_mac.launch new file mode 100644 index 00000000..47fbfd51 --- /dev/null +++ b/launch/modem_sim_tdma_test_mac.launch @@ -0,0 +1,75 @@ +<launch> + <env name="ROSCONSOLE_FORMAT" value="[${severity}] [${time}] [${node}]: ${message}"/> + + <group ns="modem0"> + <node name="modem_sim_node" pkg="ros_acomms" type="modem_sim_node.py" output="screen" > + <param name="center_frequency_hz" value="10000" type="int" /> + <param name="bandwidth_hz" value="5000" type="int" /> + <param name="SRC" value="0" type="int" /> + <param name="modem_location_source" value="local_service" /> + </node> + + <node name="tdma_test_mac" pkg="ros_acomms" type="tdma_test_mac_node.py" respawn="true" respawn_delay="10" output="screen"> + <rosparam param="tdma_test_plan" command="load" file="$(dirname)/tdma_test_plan.yaml" /> + <rosparam> + active_slots: 0 + num_slots: 2 + slot_duration_seconds: 15 + guard_time_seconds: 2 + </rosparam> + </node> + + <node name="message_queue" pkg="ros_acomms" type="message_queue_node.py" respawn="true" respawn_delay="30"> + <rosparam param="packet_codecs" command="load" file="$(dirname)/message_codec_config_traffic_gen.yaml" /> + </node> + <node name="packet_dispatch" pkg="ros_acomms" type="packet_dispatch_node.py" respawn="true" respawn_delay="30" > + <rosparam param="packet_codecs" command="load" file="$(dirname)/message_codec_config_traffic_gen.yaml" /> + </node> + + <node name="noise_model" pkg="ros_acomms" type="simple_noise_model_node.py" output="screen"> + <rosparam> + mean_noise_db: 63.0 + noise_stddev_db: 4.0 + update_every_seconds: 10 + </rosparam> + </node> + </group> + + <group ns="modem1"> + <node name="modem_sim_node" pkg="ros_acomms" type="modem_sim_node.py" output="screen" > + <param name="center_frequency_hz" value="10000" type="int" /> + <param name="bandwidth_hz" value="5000" type="int" /> + <param name="SRC" value="1" type="int" /> + <param name="modem_location_source" value="local_service" /> + </node> + + <node name="tdma_test_mac" pkg="ros_acomms" type="tdma_test_mac_node.py" respawn="true" respawn_delay="10" output="screen"> + <rosparam param="tdma_test_plan" command="load" file="$(dirname)/tdma_test_plan.yaml" /> + <rosparam> + active_slots: 1 + num_slots: 2 + slot_duration_seconds: 15 + guard_time_seconds: 2 + </rosparam> + </node> + + <node name="noise_model" pkg="ros_acomms" type="simple_noise_model_node.py" output="screen"> + <rosparam> + mean_noise_db: 60.0 + noise_stddev_db: 3.0 + update_every_seconds: 10 + </rosparam> + </node> + </group> + + <node name="sim_packet_performance_node" pkg="ros_acomms" type="sim_packet_performance_node.py" output="screen" /> + + <node name="platform_location_node" pkg="ros_acomms" type="platform_location_node.py" output="screen" /> + + <node name="sim_transmission_loss_node" pkg="ros_acomms" type="sim_transmission_loss_node.py" output="screen" > + <param name="water_depth" value="20" type="int" /> + <param name="bellhop_arrivals" value="false" type="bool" /> + </node> + + <!-- <node name="test_modem_sim_node" pkg="ros_acomms" type="test_modem_sim_node.py" output="screen" /> --> +</launch> diff --git a/launch/tdma_test_plan.yaml b/launch/tdma_test_plan.yaml new file mode 100644 index 00000000..c8fa251e --- /dev/null +++ b/launch/tdma_test_plan.yaml @@ -0,0 +1,18 @@ +test_cycle: + - miniframe_rate: 1 + dataframe_rate: 1 + maximum_miniframe_bytes: 72 + maximum_dataframe_bytes: 192 + packet_tx_count: 1 + + # - miniframe_rate: 3 + # dataframe_rate: 3 + # maximum_miniframe_bytes: 72 + # maximum_dataframe_bytes: 512 + # packet_tx_count: 2 + + - miniframe_rate: 5 + dataframe_rate: 5 + maximum_miniframe_bytes: 72 + maximum_dataframe_bytes: 2048 + packet_tx_count: 3 diff --git a/msg/TdmaTestMacStatus.msg b/msg/TdmaTestMacStatus.msg new file mode 100644 index 00000000..7ab3df50 --- /dev/null +++ b/msg/TdmaTestMacStatus.msg @@ -0,0 +1,14 @@ +Header header + +int8 miniframe_rate +int8 dataframe_rate +int32 maximum_miniframe_bytes +int32 maximum_dataframe_bytes + +int8 last_miniframe_rate +int8 last_dataframe_rate +int32 last_maximum_miniframe_bytes +int32 last_maximum_dataframe_bytes + +int16 tx_count +int16 tx_total diff --git a/src/tdma_test_mac_node.py b/src/tdma_test_mac_node.py new file mode 100755 index 00000000..8493d3cc --- /dev/null +++ b/src/tdma_test_mac_node.py @@ -0,0 +1,146 @@ +#!/usr/bin/env python3 + +import rospy +from std_msgs.msg import Header +from ros_acomms.msg import Packet, TdmaStatus, TdmaTestMacStatus +# from dynamic_reconfigure.server import Server as DynamicReconfigureServer +import struct +import datetime +import dateutil.parser + +from tdma_node import TdmaMacNode, FDPMaxBytes4Rate + +class TdmaTestMacNode(TdmaMacNode): + def __init__(self): + rospy.init_node('tdma_test_mac') + super().__init__(subclass=True) + + self.tdma_status_publisher = rospy.Publisher('tdma_status', TdmaStatus, queue_size=10) + self.tdma_test_mac_status_publisher = rospy.Publisher('tdma_test_mac_status', TdmaTestMacStatus, queue_size=10) + + # grab test plan (defined in yaml) + self.test_plan = rospy.get_param('~tdma_test_plan', None) + if self.test_plan: + # we have a test plan! set starting index at 0 + self.current_test_index = 0 + self.tx_count = 0 + self.tx_total = 1 + + # setup dynamic reconf for periodic ping params + # self.first_dynamic_reconf = True + # self.reconfigure_server = DynamicReconfigureServer(tdma_nav_headerConfig, self.reconfigure) + + rospy.loginfo("tdma_test_mac running") + self.spin() + + # def reconfigure(self, config, level): + # if self.first_dynamic_reconf: + # self.first_dynamic_reconf = False + # # due to way rosparam of typle list doesn't properly map to param server in launch file + # # ..meaning the defaults set in the .cfg file will always use those values at first call + # # ..so to avoid having defaults set (when ros handles this by calling all non-list type ros params from param server), + # # ..set values from init in config + # rospy.loginfo(f'First dynamic_reconfigure call, syncing config from init') + # return config + + # rospy.loginfo("tdma_test_mac driver reconfigure request received.") + # rospy.loginfo(f"config: {config}") + # return config + + def get_test_params(self): + if self.test_plan: + if self.current_test_index >= len(self.test_plan['test_cycle']): + # back to the begining + self.current_test_index = 0 + self.tx_count = 0 + + test_params = self.test_plan['test_cycle'][self.current_test_index] + self.tx_total = test_params.get('packet_tx_count', 1) + self.tx_count += 1 + + rospy.loginfo(f'Current test params: {test_params}') + fdp_mini = FDPMaxBytes4Rate(rate=test_params['miniframe_rate'], max_bytes=test_params['maximum_miniframe_bytes'], default=None) + fdp_data = FDPMaxBytes4Rate(rate=test_params['dataframe_rate'], max_bytes=test_params['maximum_dataframe_bytes'], default=None) + + if self.tx_total == 1: + tx_count_stateless = 1 + else: + tx_count_stateless = self.tx_count + + if self.tx_count >= self.tx_total or self.tx_total == 1: + rospy.loginfo(f'Last TX with these settings') + # last tx with these setting + self.current_test_index += 1 + self.tx_count = 0 # set state for next call + else: + fdp_mini = FDPMaxBytes4Rate(rate=self.miniframe_rate, max_bytes=self.maximum_miniframe_bytes, default=None) + fdp_data = FDPMaxBytes4Rate(rate=self.dataframe_rate, max_bytes=self.maximum_dataframe_bytes, default=None) + + rospy.loginfo(f"Returning: {fdp_mini}, {fdp_data}, {tx_count_stateless}") + rospy.loginfo(f"TX'd with these settings: {tx_count_stateless} /of/ {self.tx_total} times") + return fdp_mini, fdp_data, tx_count_stateless + + def set_rate_max_bytes_for_next_tx(self): + fdp_mini, fdp_data, tx_count_stateless = self.get_test_params() + + msg = TdmaTestMacStatus() + msg.header.stamp = rospy.Time.now() + msg.last_miniframe_rate = self.miniframe_rate + msg.last_dataframe_rate = self.dataframe_rate + msg.last_maximum_miniframe_bytes = self.maximum_miniframe_bytes + msg.last_maximum_dataframe_bytes = self.maximum_dataframe_bytes + + msg.tx_count = tx_count_stateless # num of times we have tx'd with the current settings (including this time) + msg.tx_total = self.tx_total # num of times we will use these settings before moving on to the next test + + # now set class attrs for next tx according to test yaml + self.miniframe_rate = fdp_mini.rate + self.dataframe_rate = fdp_data.rate + self.maximum_miniframe_bytes = fdp_mini.max_bytes + self.maximum_dataframe_bytes = fdp_data.max_bytes + + # grab actual attrs values after validation + msg.miniframe_rate = self.miniframe_rate + msg.dataframe_rate = self.dataframe_rate + msg.maximum_miniframe_bytes = self.maximum_miniframe_bytes + msg.maximum_dataframe_bytes = self.maximum_dataframe_bytes + + self.tdma_test_mac_status_publisher.publish(msg) + rospy.logdebug(f'Changed rate and max bytes for next TX:\n{msg}') + + def spin(self): + rate = rospy.Rate(5) + last_tx_time = 0 + + while not rospy.is_shutdown(): + we_are_active, current_slot, remaining_slot_seconds, remaining_active_seconds, time_to_next_active = self.get_current_slot_info() + if not we_are_active: + rate.sleep() + continue + + # Make sure we have enough time left to send a packet + if remaining_active_seconds < (self.guard_time_seconds + self.packet_length_seconds): + rate.sleep() + continue + + # Make sure that the modem is ready to accept a packet + # TODO: Check modem state here rather than relying on last_tx_time. + # Note that this isn't atomic, so the state could change + if rospy.get_time() <= (last_tx_time + self.guard_time_seconds + self.packet_length_seconds) or \ + rospy.get_time() <= self.last_txf_time + self.guard_time_seconds: + rate.sleep() + continue + + self.set_rate_max_bytes_for_next_tx() + self.send_next_packet() + + last_tx_time = rospy.get_time() + +if __name__ == "__main__": + try: + tdma_state_node = TdmaTestMacNode() + + except rospy.ROSInterruptException: + rospy.loginfo("tdma_test_mac_node shutdown (interrupt)") + + -- GitLab From 847ac7f5b08044ba376a6d101c362666c2e7e2e5 Mon Sep 17 00:00:00 2001 From: caileighf <caileighfitzgerald@gmail.com> Date: Thu, 11 May 2023 03:03:10 +0000 Subject: [PATCH 2/4] test plan settings can leave maximum_Tframe_bytes out and the test tdma node will use the default value for the rate --- launch/tdma_test_plan.yaml | 3 +++ src/tdma_test_mac_node.py | 18 ++++++++++++++++-- 2 files changed, 19 insertions(+), 2 deletions(-) diff --git a/launch/tdma_test_plan.yaml b/launch/tdma_test_plan.yaml index c8fa251e..af4b0d25 100644 --- a/launch/tdma_test_plan.yaml +++ b/launch/tdma_test_plan.yaml @@ -1,4 +1,7 @@ test_cycle: + - miniframe_rate: 1 + dataframe_rate: 1 + - miniframe_rate: 1 dataframe_rate: 1 maximum_miniframe_bytes: 72 diff --git a/src/tdma_test_mac_node.py b/src/tdma_test_mac_node.py index 8493d3cc..a7b24622 100755 --- a/src/tdma_test_mac_node.py +++ b/src/tdma_test_mac_node.py @@ -59,8 +59,22 @@ class TdmaTestMacNode(TdmaMacNode): self.tx_count += 1 rospy.loginfo(f'Current test params: {test_params}') - fdp_mini = FDPMaxBytes4Rate(rate=test_params['miniframe_rate'], max_bytes=test_params['maximum_miniframe_bytes'], default=None) - fdp_data = FDPMaxBytes4Rate(rate=test_params['dataframe_rate'], max_bytes=test_params['maximum_dataframe_bytes'], default=None) + fdp_mini = FDPMaxBytes4Rate( + rate=test_params['miniframe_rate'], + max_bytes=test_params.get( + 'maximum_miniframe_bytes', + TdmaMacNode.FDP_MAX_BYTES_FOR_MINI_RATE[test_params['miniframe_rate']].default + ), + default=None + ) + fdp_data = FDPMaxBytes4Rate( + rate=test_params['dataframe_rate'], + max_bytes=test_params.get( + 'maximum_dataframe_bytes', + TdmaMacNode.FDP_MAX_BYTES_FOR_DATA_RATE[test_params['dataframe_rate']].default + ), + default=None + ) if self.tx_total == 1: tx_count_stateless = 1 -- GitLab From 272e3c1a2331d0138ce9de9abfea322c16001d34 Mon Sep 17 00:00:00 2001 From: caileighf <caileighfitzgerald@gmail.com> Date: Thu, 11 May 2023 03:29:08 +0000 Subject: [PATCH 3/4] Made log output better, removed uneeded blocks from the launch file for modem1 --- launch/modem_sim_tdma_test_mac.launch | 12 +----------- src/tdma_test_mac_node.py | 3 +-- 2 files changed, 2 insertions(+), 13 deletions(-) diff --git a/launch/modem_sim_tdma_test_mac.launch b/launch/modem_sim_tdma_test_mac.launch index 47fbfd51..ed681699 100644 --- a/launch/modem_sim_tdma_test_mac.launch +++ b/launch/modem_sim_tdma_test_mac.launch @@ -13,7 +13,7 @@ <rosparam param="tdma_test_plan" command="load" file="$(dirname)/tdma_test_plan.yaml" /> <rosparam> active_slots: 0 - num_slots: 2 + num_slots: 1 slot_duration_seconds: 15 guard_time_seconds: 2 </rosparam> @@ -43,16 +43,6 @@ <param name="modem_location_source" value="local_service" /> </node> - <node name="tdma_test_mac" pkg="ros_acomms" type="tdma_test_mac_node.py" respawn="true" respawn_delay="10" output="screen"> - <rosparam param="tdma_test_plan" command="load" file="$(dirname)/tdma_test_plan.yaml" /> - <rosparam> - active_slots: 1 - num_slots: 2 - slot_duration_seconds: 15 - guard_time_seconds: 2 - </rosparam> - </node> - <node name="noise_model" pkg="ros_acomms" type="simple_noise_model_node.py" output="screen"> <rosparam> mean_noise_db: 60.0 diff --git a/src/tdma_test_mac_node.py b/src/tdma_test_mac_node.py index a7b24622..c403f749 100755 --- a/src/tdma_test_mac_node.py +++ b/src/tdma_test_mac_node.py @@ -90,8 +90,7 @@ class TdmaTestMacNode(TdmaMacNode): fdp_mini = FDPMaxBytes4Rate(rate=self.miniframe_rate, max_bytes=self.maximum_miniframe_bytes, default=None) fdp_data = FDPMaxBytes4Rate(rate=self.dataframe_rate, max_bytes=self.maximum_dataframe_bytes, default=None) - rospy.loginfo(f"Returning: {fdp_mini}, {fdp_data}, {tx_count_stateless}") - rospy.loginfo(f"TX'd with these settings: {tx_count_stateless} /of/ {self.tx_total} times") + rospy.loginfo(f"{tx_count_stateless} /of/ {self.tx_total} times. Returning: {fdp_mini}, {fdp_data}, {tx_count_stateless}") return fdp_mini, fdp_data, tx_count_stateless def set_rate_max_bytes_for_next_tx(self): -- GitLab From 435a502300383c3b00668b4df2560e311346861d Mon Sep 17 00:00:00 2001 From: caileighf <caileighfitzgerald@gmail.com> Date: Thu, 11 May 2023 04:11:42 +0000 Subject: [PATCH 4/4] added packet duration to FDP rate named tuple from manual FDP table. Can use static value passed to tdma node, use the values in the test plan OR if ommited, use the default values for the packet duration (according to the table) according to rate and type (data/mini). Includes [this] tdma calls settings, the last and now packet length in seconds (max supported for [this] tdma call) --- launch/modem_sim_tdma_test_mac.launch | 1 + msg/TdmaTestMacStatus.msg | 2 ++ src/tdma_node.py | 14 ++++---- src/tdma_test_mac_node.py | 51 ++++++++++++++------------- 4 files changed, 37 insertions(+), 31 deletions(-) diff --git a/launch/modem_sim_tdma_test_mac.launch b/launch/modem_sim_tdma_test_mac.launch index ed681699..b1b90de6 100644 --- a/launch/modem_sim_tdma_test_mac.launch +++ b/launch/modem_sim_tdma_test_mac.launch @@ -16,6 +16,7 @@ num_slots: 1 slot_duration_seconds: 15 guard_time_seconds: 2 + use_test_plan_packet_duration: True </rosparam> </node> diff --git a/msg/TdmaTestMacStatus.msg b/msg/TdmaTestMacStatus.msg index 7ab3df50..f5973e0d 100644 --- a/msg/TdmaTestMacStatus.msg +++ b/msg/TdmaTestMacStatus.msg @@ -12,3 +12,5 @@ int32 last_maximum_dataframe_bytes int16 tx_count int16 tx_total + +int16 packet_length_seconds diff --git a/src/tdma_node.py b/src/tdma_node.py index eee079a7..bc78f1b9 100755 --- a/src/tdma_node.py +++ b/src/tdma_node.py @@ -10,20 +10,20 @@ import datetime import dateutil.parser from collections import namedtuple -FDPMaxBytes4Rate = namedtuple('FDPMaxBytes4Rate', 'rate max_bytes default') +FDPMaxBytes4Rate = namedtuple('FDPMaxBytes4Rate', 'rate max_bytes default packet_duration_ms') class TdmaMacNode(object): FDP_MAX_BYTES_FOR_MINI_RATE = [ - None, FDPMaxBytes4Rate(rate=1, max_bytes=96, default=72), # index 1, rate 1 - None, FDPMaxBytes4Rate(rate=3, max_bytes=96, default=72), # index 3, rate 3 - None, FDPMaxBytes4Rate(rate=5, max_bytes=96, default=72), # index 5, rate 5 + None, FDPMaxBytes4Rate(rate=1, max_bytes=96, default=72, packet_duration_ms=1574), # index 1, rate 1 + None, FDPMaxBytes4Rate(rate=3, max_bytes=96, default=72, packet_duration_ms=755), # index 3, rate 3 + None, FDPMaxBytes4Rate(rate=5, max_bytes=96, default=72, packet_duration_ms=286), # index 5, rate 5 None, None, None, None, None, None, None, ] FDP_MAX_BYTES_FOR_DATA_RATE = [ - None, FDPMaxBytes4Rate(rate=1, max_bytes=192, default=192), # index 1, rate 1 - None, FDPMaxBytes4Rate(rate=3, max_bytes=512, default=512), # index 3, rate 3 - None, FDPMaxBytes4Rate(rate=5, max_bytes=2048, default=2048), # index 5, rate 5 + None, FDPMaxBytes4Rate(rate=1, max_bytes=192, default=192, packet_duration_ms=3072), # index 1, rate 1 + None, FDPMaxBytes4Rate(rate=3, max_bytes=512, default=512, packet_duration_ms=3072), # index 3, rate 3 + None, FDPMaxBytes4Rate(rate=5, max_bytes=2048, default=2048, packet_duration_ms=3000), # index 5, rate 5 None, None, None, None, None, None, None, ] diff --git a/src/tdma_test_mac_node.py b/src/tdma_test_mac_node.py index c403f749..f64d7177 100755 --- a/src/tdma_test_mac_node.py +++ b/src/tdma_test_mac_node.py @@ -3,7 +3,6 @@ import rospy from std_msgs.msg import Header from ros_acomms.msg import Packet, TdmaStatus, TdmaTestMacStatus -# from dynamic_reconfigure.server import Server as DynamicReconfigureServer import struct import datetime import dateutil.parser @@ -20,33 +19,16 @@ class TdmaTestMacNode(TdmaMacNode): # grab test plan (defined in yaml) self.test_plan = rospy.get_param('~tdma_test_plan', None) + self.use_test_plan_packet_duration = rospy.get_param('~use_test_plan_packet_duration', False) if self.test_plan: # we have a test plan! set starting index at 0 self.current_test_index = 0 self.tx_count = 0 self.tx_total = 1 - - # setup dynamic reconf for periodic ping params - # self.first_dynamic_reconf = True - # self.reconfigure_server = DynamicReconfigureServer(tdma_nav_headerConfig, self.reconfigure) rospy.loginfo("tdma_test_mac running") self.spin() - # def reconfigure(self, config, level): - # if self.first_dynamic_reconf: - # self.first_dynamic_reconf = False - # # due to way rosparam of typle list doesn't properly map to param server in launch file - # # ..meaning the defaults set in the .cfg file will always use those values at first call - # # ..so to avoid having defaults set (when ros handles this by calling all non-list type ros params from param server), - # # ..set values from init in config - # rospy.loginfo(f'First dynamic_reconfigure call, syncing config from init') - # return config - - # rospy.loginfo("tdma_test_mac driver reconfigure request received.") - # rospy.loginfo(f"config: {config}") - # return config - def get_test_params(self): if self.test_plan: if self.current_test_index >= len(self.test_plan['test_cycle']): @@ -65,7 +47,11 @@ class TdmaTestMacNode(TdmaMacNode): 'maximum_miniframe_bytes', TdmaMacNode.FDP_MAX_BYTES_FOR_MINI_RATE[test_params['miniframe_rate']].default ), - default=None + default=None, + packet_duration_ms=test_params.get( + 'packet_duration_ms', + TdmaMacNode.FDP_MAX_BYTES_FOR_MINI_RATE[test_params['miniframe_rate']].packet_duration_ms + ) ) fdp_data = FDPMaxBytes4Rate( rate=test_params['dataframe_rate'], @@ -73,7 +59,11 @@ class TdmaTestMacNode(TdmaMacNode): 'maximum_dataframe_bytes', TdmaMacNode.FDP_MAX_BYTES_FOR_DATA_RATE[test_params['dataframe_rate']].default ), - default=None + default=None, + packet_duration_ms=test_params.get( + 'packet_duration_ms', + TdmaMacNode.FDP_MAX_BYTES_FOR_DATA_RATE[test_params['dataframe_rate']].packet_duration_ms + ) ) if self.tx_total == 1: @@ -87,8 +77,8 @@ class TdmaTestMacNode(TdmaMacNode): self.current_test_index += 1 self.tx_count = 0 # set state for next call else: - fdp_mini = FDPMaxBytes4Rate(rate=self.miniframe_rate, max_bytes=self.maximum_miniframe_bytes, default=None) - fdp_data = FDPMaxBytes4Rate(rate=self.dataframe_rate, max_bytes=self.maximum_dataframe_bytes, default=None) + fdp_mini = FDPMaxBytes4Rate(rate=self.miniframe_rate, max_bytes=self.maximum_miniframe_bytes, default=None, packet_duration_ms=TdmaMacNode.FDP_MAX_BYTES_FOR_MINI_RATE[self.miniframe_rate].packet_duration_ms) + fdp_data = FDPMaxBytes4Rate(rate=self.dataframe_rate, max_bytes=self.maximum_dataframe_bytes, default=None, packet_duration_ms=TdmaMacNode.FDP_MAX_BYTES_FOR_MINI_RATE[self.dataframe_rate].packet_duration_ms) rospy.loginfo(f"{tx_count_stateless} /of/ {self.tx_total} times. Returning: {fdp_mini}, {fdp_data}, {tx_count_stateless}") return fdp_mini, fdp_data, tx_count_stateless @@ -102,6 +92,7 @@ class TdmaTestMacNode(TdmaMacNode): msg.last_dataframe_rate = self.dataframe_rate msg.last_maximum_miniframe_bytes = self.maximum_miniframe_bytes msg.last_maximum_dataframe_bytes = self.maximum_dataframe_bytes + msg.packet_length_seconds = self.packet_length_seconds msg.tx_count = tx_count_stateless # num of times we have tx'd with the current settings (including this time) msg.tx_total = self.tx_total # num of times we will use these settings before moving on to the next test @@ -121,11 +112,23 @@ class TdmaTestMacNode(TdmaMacNode): self.tdma_test_mac_status_publisher.publish(msg) rospy.logdebug(f'Changed rate and max bytes for next TX:\n{msg}') + return fdp_mini.packet_duration_ms + fdp_data.packet_duration_ms + + def handle_packet_duration(self, packet_duration_seconds): + # if use_test_plan_packet_duration, we set supers packet duration with user entered (in yaml OR default for rate) + # .. otherwise, tdma default behavior, use packet_length_seconds passed (defaults to 5?) + if self.use_test_plan_packet_duration: + self.packet_length_seconds = packet_duration_seconds + def spin(self): rate = rospy.Rate(5) last_tx_time = 0 + packet_duration_ms = None while not rospy.is_shutdown(): + if packet_duration_ms: + self.handle_packet_duration(packet_duration_seconds=packet_duration_ms // 1000) + we_are_active, current_slot, remaining_slot_seconds, remaining_active_seconds, time_to_next_active = self.get_current_slot_info() if not we_are_active: rate.sleep() @@ -144,7 +147,7 @@ class TdmaTestMacNode(TdmaMacNode): rate.sleep() continue - self.set_rate_max_bytes_for_next_tx() + packet_duration_ms = self.set_rate_max_bytes_for_next_tx() self.send_next_packet() last_tx_time = rospy.get_time() -- GitLab