diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml
index 18ea38f8ad878371a19ee1f8b73590f3161205ad..23e441de77d970973cf81e0cc9c046b612068303 100644
--- a/.gitlab-ci.yml
+++ b/.gitlab-ci.yml
@@ -40,18 +40,18 @@ trigger-ros_acomms_net_tools-pipeline:
   except:
     - dev/autodocs
 
-gitlab run_tests:
+.run_tests_base: &run_tests_base
   stage: test
   image: ros_acomms-tests:latest
   script:
     - source /ros_entrypoint.sh
     - mkdir -p ~/catkin_ws/src
     - cd ../ && mv $CI_PROJECT_NAME ~/catkin_ws/src/
-    - git clone -b $PYACOMMS_BRANCH https://gitlab-ci-token:$CI_JOB_TOKEN@git.whoi.edu/acomms/pyacomms.git ~/pyacomms
-    - git clone -b $LTCODEC_BRANCH https://gitlab-ci-token:$CI_JOB_TOKEN@git.whoi.edu/acomms/ltcodec.git ~/ltcodec
+    - if [[ $TEST_LIBRARIES_FROM_GIT ]]; then git clone -b $PYACOMMS_BRANCH https://gitlab-ci-token:$CI_JOB_TOKEN@git.whoi.edu/acomms/pyacomms.git ~/pyacomms; fi
+    - if [[ $TEST_LIBRARIES_FROM_GIT ]]; then git clone -b $LTCODEC_BRANCH https://gitlab-ci-token:$CI_JOB_TOKEN@git.whoi.edu/acomms/ltcodec.git ~/ltcodec; fi
     - cd ~/catkin_ws/src/ros_acomms && pip install -U -r requirements.txt
-    - cd ~/ltcodec && pip install .
-    - cd ~/pyacomms && pip install .
+    - if [[ $TEST_LIBRARIES_FROM_GIT ]]; then cd ~/ltcodec && pip install .; fi
+    - if [[ $TEST_LIBRARIES_FROM_GIT ]]; then cd ~/pyacomms && pip install .; fi
     - cd ~/catkin_ws && catkin_make
     - roscore &
     - sleep 5
@@ -59,30 +59,38 @@ gitlab run_tests:
     - rosparam set /clock_generator/multiplier $CLOCK_MULTIPLIER
     - rosparam set /clock_generator/publish_rate $CLOCK_PUBLISH_RATE
     - source devel/setup.bash
-    - rosrun ros_acomms_tests test_ros_acomms.py
-    - rosrun ros_acomms_tests test_dynamic_queue.py
+    - rosrun ros_acomms_tests test_ros_acomms.py _tdma_type:=$TDMA_TYPE
+    - if [[ $TEST_DYNAMIC_QUEUES ]]; then rosrun ros_acomms_tests test_dynamic_queue.py _tdma_type:=$TDMA_TYPE; fi
   except:
     - dev/autodocs
 
-pypi run_tests:
-  stage: test
-  image: ros_acomms-tests:latest
-  script:
-    - source /ros_entrypoint.sh
-    - mkdir -p ~/catkin_ws/src
-    - cd ../ && mv $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
-    - rosparam set /ros_acomms_tests/fragmentation_test_msg_size $MSG_SIZE
-    - rosparam set /clock_generator/multiplier $CLOCK_MULTIPLIER
-    - rosparam set /clock_generator/publish_rate $CLOCK_PUBLISH_RATE
-    - source devel/setup.bash
-    - rosrun ros_acomms_tests test_ros_acomms.py
-    - rosrun ros_acomms_tests test_dynamic_queue.py
-  except:
-    - dev/autodocs
+gitlab run_tests:
+  <<: *run_tests_base
+  variables:
+    TEST_LIBRARIES_FROM_GIT: "true"
+    TEST_DYNAMIC_QUEUES: "true"
+    TDMA_TYPE: "tdma"
+
+pypi-basic-tdma run_tests:
+  <<: *run_tests_base
+  variables:
+    TEST_LIBRARIES_FROM_GIT: ""
+    TEST_DYNAMIC_QUEUES: "true"
+    TDMA_TYPE: "tdma"
+
+pypi-advanced-tdma run_tests:
+  <<: *run_tests_base
+  variables:
+    TEST_LIBRARIES_FROM_GIT: ""
+    TEST_DYNAMIC_QUEUES: "true"
+    TDMA_TYPE: "tdma_advanced"
+
+pypi-scripted-tdma run_tests:
+  <<: *run_tests_base
+  variables:
+    TEST_LIBRARIES_FROM_GIT: ""
+    TEST_DYNAMIC_QUEUES: "true"
+    TDMA_TYPE: "tdma_scripted"
 
 auto-docs-pdf:
   image: ros_acomms-docs:latest
diff --git a/docs/ros_acomms/tdma_advanced_node.rst b/docs/ros_acomms/tdma_advanced_node.rst
new file mode 100644
index 0000000000000000000000000000000000000000..e4cc79e5dfe08486d6a6c5fc82450bd427b39a72
--- /dev/null
+++ b/docs/ros_acomms/tdma_advanced_node.rst
@@ -0,0 +1,7 @@
+tdma\_advanced\_node module
+===========================
+
+.. automodule:: tdma_advanced_node
+   :members:
+   :undoc-members:
+   :show-inheritance:
diff --git a/docs/ros_acomms/tdma_nav_header_node.rst b/docs/ros_acomms/tdma_nav_header_node.rst
deleted file mode 100644
index a620f3e28593837b0101efff92c772126969d101..0000000000000000000000000000000000000000
--- a/docs/ros_acomms/tdma_nav_header_node.rst
+++ /dev/null
@@ -1,7 +0,0 @@
-tdma\_nav\_header\_node module
-==============================
-
-.. automodule:: tdma_nav_header_node
-   :members:
-   :undoc-members:
-   :show-inheritance:
diff --git a/docs/ros_acomms/tdma_scripted_node.rst b/docs/ros_acomms/tdma_scripted_node.rst
new file mode 100644
index 0000000000000000000000000000000000000000..14620d1fd6550acbe486694e3780a7bab1ded87d
--- /dev/null
+++ b/docs/ros_acomms/tdma_scripted_node.rst
@@ -0,0 +1,7 @@
+tdma\_scripted\_node module
+===========================
+
+.. automodule:: tdma_scripted_node
+   :members:
+   :undoc-members:
+   :show-inheritance:
diff --git a/docs/ros_acomms/tdma_test_mac_node.rst b/docs/ros_acomms/tdma_test_mac_node.rst
deleted file mode 100644
index e10bc32b2f46e7fa5705f3bb6c79450a2c841d28..0000000000000000000000000000000000000000
--- a/docs/ros_acomms/tdma_test_mac_node.rst
+++ /dev/null
@@ -1,7 +0,0 @@
-tdma\_test\_mac\_node module
-============================
-
-.. automodule:: tdma_test_mac_node
-   :members:
-   :undoc-members:
-   :show-inheritance:
diff --git a/requirements.txt b/requirements.txt
index 6b8a6be5d6a9b7c816fd0482e99e8103be21cefc..a2c2cabd30465208debd6ca11d4e5b9cee52c172 100755
--- a/requirements.txt
+++ b/requirements.txt
@@ -13,4 +13,5 @@ whoi-gitver
 acomms>=2.4.0
 importlib-metadata
 pyyaml
-rospy-yaml-include
\ No newline at end of file
+rospy-yaml-include
+croniter
diff --git a/ros_acomms/CMakeLists.txt b/ros_acomms/CMakeLists.txt
index 4ad2b534164debe29be0ae5298ba47cd4cdc8721..4706336d720302997593bf647d25a9771538e5cc 100755
--- a/ros_acomms/CMakeLists.txt
+++ b/ros_acomms/CMakeLists.txt
@@ -72,7 +72,8 @@ catkin_python_setup()
 ## Generate dynamic reconfigure parameters in the 'cfg' folder
 generate_dynamic_reconfigure_options(
    cfg/acomms_driver.cfg
-   cfg/tdma_nav_header.cfg
+   cfg/tdma_advanced.cfg
+   cfg/tdma_scripted.cfg
 )
 
 ###################################
diff --git a/ros_acomms/cfg/tdma_advanced.cfg b/ros_acomms/cfg/tdma_advanced.cfg
new file mode 100755
index 0000000000000000000000000000000000000000..44e7b8ec8b5d675d203a6ce24e4ea70594c144bc
--- /dev/null
+++ b/ros_acomms/cfg/tdma_advanced.cfg
@@ -0,0 +1,50 @@
+#! /usr/bin/env python
+import roslib
+from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, int_t, bool_t, str_t
+
+PACKAGE = 'ros_acomms'
+
+roslib.load_manifest(PACKAGE)
+
+gen = ParameterGenerator()
+
+# Name, Type, Level, Description, Default, Min, Max
+gen.add("skew_cycle_sec", int_t, 0, "Skew cycle_start_time +/- offset in seconds", 0, -3600, 3600) # +1 hour, -1 hour
+gen.add("software_mute", bool_t, 0, "Software mute, when muted, tdma won't transmit", False)   # when muted, tdma won't transmit
+
+gen.add("num_slots", int_t, 0, "num_slots", 4, 1, 1000)  # num_slots max 1000 (arbitrary)
+gen.add("active_slots_", str_t, 0, "active_slots - single int as a string or list of ints comma separated", "0")  # active_slots
+gen.add("nav_slots_", str_t, 0, "nav_slots, slots to allow nav pings (CCCMD,PNG/CCPDT,,), default allow all slots - single int as a string or list of ints comma separated", "0")  # nav_slots
+gen.add("comms_slots_", str_t, 0, "comms_slots, slots to allows comms packets (fdp), default allow all slots - single int as a string or list of ints comma separated", "0")  # comms_slots
+gen.add("slot_duration_seconds", int_t, 0, "slot_duration_seconds", 30, 0, 28800)  # slot_duration_seconds max 8 hrs (arbitrary)
+gen.add("guard_time_seconds", int_t, 0, "guard_time_seconds", 5, 0, 28800)  # guard_time_seconds max 8 hrs (arbitrary)
+gen.add("packet_length_seconds", int_t, 0, "packet_length_seconds", 5, 0, 28800)  # packet_length_seconds max 8 hrs (arbitrary)
+
+gen.add("ping_modem", bool_t, 0, "Ping modem toggle", False) # Ping Modem toggle 
+gen.add("ping_modem_timeout_sec", int_t, 0, "Modem src id that will be used in TWTT ping", 5, 5, 500)  # timeout for waiting for reply to ping (this is blocking on TDMA!)
+gen.add("ping_modem_src", int_t, 0, "Modem src id that will be used in TWTT ping", 12, 0, 255)  # $CCCMD,PNG,SRC,ping_modem_src,...
+gen.add("pings_per_slot", int_t, 0, "Number of TWTT pings to send to EACH ping_modem_src in ping_modem_srcs *no handling for taking up whole slot*", 0, 0, 15) # defaults to 0, if software_mute = True, no pings
+                                                                                                # how many times to send, $CCCMD,PNG,SRC,ping_modem_src,...
+cdr_enum = gen.enum([ gen.const("UNIX_EPOCH", int_t, 4, "Epoch TOT of ping reply"),
+			          gen.const("MS_PAST_HR", int_t, 8, "ms past the hour TOT of ping reply")],
+			          "Ping CDR")
+gen.add("ping_cdr", int_t, 0, "TWTT ping CDR, only options are 04 epoch, 08 ms past the hour", 4, 4, 8, edit_method=cdr_enum)
+
+gen.add("ping_transponders", bool_t, 0, "Ping REMUS transponder group", False) # Ping REMUS transponder group toggled on
+gen.add("ping_transponder_a", bool_t, 0, "Ping REMUS transponder A", True) # Ping REMUS transponder A, only happens when ping_transponders == True
+gen.add("ping_transponder_b", bool_t, 0, "Ping REMUS transponder B", True) # Ping REMUS transponder B
+gen.add("ping_transponder_c", bool_t, 0, "Ping REMUS transponder C", True) # Ping REMUS transponder C
+gen.add("ping_transponder_d", bool_t, 0, "Ping REMUS transponder D", True) # Ping REMUS transponder D
+
+rate_enum = gen.enum([ gen.const("RELIABLE_RATE", int_t, 1, "Slower, most reliable"),
+			           gen.const("FASTER_RATE", int_t, 3, "Faster, less reliable"),
+			           gen.const("FASTEST_RATE", int_t, 5, "Fastest, least reliable")],
+			           "PSK-FDP rates")
+
+gen.add("miniframe_rate", int_t, 0, "miniframe_rate", 1, 0, 5, edit_method=rate_enum)
+gen.add("dataframe_rate", int_t, 0, "dataframe_rate", 1, 0, 5, edit_method=rate_enum)
+
+# The second parameter is the name of a node this could run in (used to generate documentation only),
+# the third parameter is a name prefix the generated files will get (e.g. "<name>Config.h" for c++, or "<name>Config.py"
+# for python.
+exit(gen.generate(PACKAGE, "tdma_advanced", "tdma_advanced"))
diff --git a/ros_acomms/cfg/tdma_nav_header.cfg b/ros_acomms/cfg/tdma_nav_header.cfg
deleted file mode 100644
index cef381153d70e7be18446addc119bbb3685c6209..0000000000000000000000000000000000000000
--- a/ros_acomms/cfg/tdma_nav_header.cfg
+++ /dev/null
@@ -1,30 +0,0 @@
-#! /usr/bin/env python
-import roslib
-from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, str_t, int_t, bool_t, double_t
-
-PACKAGE = 'ros_acomms'
-
-roslib.load_manifest(PACKAGE)
-
-gen = ParameterGenerator()
-
-# Name, Type, Level, Description, Default, Min, Max
-gen.add("nav_duration_seconds", int_t, 0, "Nav portion of TDMA slot in seconds", 15, 0, 14400) # 4 hours max (arbitrary)
-gen.add("nav_guard_time_seconds", int_t, 0, "Nav portion of TDMA slot guard seconds", 5, 0, 1800) # 30 mins max (arbitrary)
-gen.add("transponder_A", bool_t, 0, "Ping transponder A", True)
-gen.add("transponder_B", bool_t, 0, "Ping transponder B", True)
-gen.add("transponder_C", bool_t, 0, "Ping transponder C", True)
-gen.add("transponder_D", bool_t, 0, "Ping transponder D", True)
-gen.add("transponder_reply_timeout_ms", int_t, 0, "Transponder reply timeout ms", 5000, 0, 300000)
-gen.add("ping_dest_id", int_t, 0, "Ping modem dest id", 1, 0, 255)
-gen.add("ping_cdr", str_t, 0, "Ping CDR field", "0x04")
-gen.add("ping_rate", int_t, 0, "Nav portion of TDMA slot guard seconds", 1, 1, 5)
-gen.add("cycle_rate_every_n_pings", int_t, 0, "cycle through rates 1,3,5 every n pings, 0 means use set rate don't change", 0, 0, 10000)
-gen.add("ping_hex_data", str_t, 0, "Ping hex data field", "")
-gen.add("ping_modem_on", bool_t, 0, "Ping modem at ping_modem_dest_id every nav portion of the TDMA slot", True)
-gen.add("ping_transponders_on", bool_t, 0, "Ping transponders at transponder_group_dest_id every nav portion of the TDMA slot", True)
-
-# The second parameter is the name of a node this could run in (used to generate documentation only),
-# the third parameter is a name prefix the generated files will get (e.g. "<name>Config.h" for c++, or "<name>Config.py"
-# for python.
-exit(gen.generate(PACKAGE, "tdma_nav_header", "tdma_nav_header"))
diff --git a/ros_acomms/cfg/tdma_scripted.cfg b/ros_acomms/cfg/tdma_scripted.cfg
new file mode 100755
index 0000000000000000000000000000000000000000..53054ad20adb9a6d6c1eff2ac41e65afac4fec0c
--- /dev/null
+++ b/ros_acomms/cfg/tdma_scripted.cfg
@@ -0,0 +1,17 @@
+#! /usr/bin/env python
+import roslib
+from dynamic_reconfigure.parameter_generator_catkin import ParameterGenerator, int_t, bool_t
+
+PACKAGE = 'ros_acomms'
+
+roslib.load_manifest(PACKAGE)
+
+gen = ParameterGenerator()
+
+# Name, Type, Level, Description, Default, Min, Max
+# gen.add("software_mute", bool_t, 0, "Software mute", False)
+
+# The second parameter is the name of a node this could run in (used to generate documentation only),
+# the third parameter is a name prefix the generated files will get (e.g. "<name>Config.h" for c++, or "<name>Config.py"
+# for python.
+exit(gen.generate(PACKAGE, "tdma_scripted", "tdma_scripted"))
diff --git a/ros_acomms/package.xml b/ros_acomms/package.xml
index 91f35845f402beebbbe6fbc876cf45cc647ebebf..bba0d02fc9410534a0353d5dd71ea559c416323a 100644
--- a/ros_acomms/package.xml
+++ b/ros_acomms/package.xml
@@ -1,30 +1,29 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>ros_acomms</name>
-  <version>6.1.0</version>
+  <version>9.0.0</version>
   <description>ROS interface to Micromodem using pyacomms</description>
 
-  <!-- One maintainer tag required, multiple allowed, one person per tag --> 
-  <!-- Example:  -->
-  <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
+  <!-- START package wide section -->
+  <!-- MAINTAINERS, Copy changes made in this section of package.xml package wide -->
+  <!-- One maintainer tag required, multiple allowed, one person per tag -->
   <maintainer email="egallimore@whoi.edu">Eric Gallimore</maintainer>
   <maintainer email="cfitzgerald@whoi.edu">Caileigh Fitzgerald</maintainer>
 
   <!-- One license tag required, multiple allowed, one license per tag -->
-  <!-- Commonly used license strings: -->
-  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
   <license>LGPLv3</license>
 
   <!-- Url tags are optional, but multiple are allowed, one per tag -->
   <!-- Optional attribute type can be: website, bugtracker, or repository -->
-  <!-- Example: -->
-  <!-- <url type="website">http://wiki.ros.org/recon</url> -->
+  <url type="website">https://acomms.pages.whoi.edu/ros_acomms/</url>
 
   <!-- Author tags are optional, multiple are allowed, one per tag -->
   <!-- Authors do not have to be maintainers, but could be -->
   <author email="egallimore@whoi.edu">Eric Gallimore</author>
   <author email="cfitzgerald@whoi.edu">Caileigh Fitzgerald</author>
   <author email="dgiaya@whoi.edu">Dennis Giaya</author>
+  <!-- MAINTAINERS, Copy changes made in this section of package.xml package wide -->
+  <!-- END package wide section -->
 
   <!-- The *_depend tags are used to specify dependencies -->
   <!-- Dependencies can be catkin packages or system dependencies -->
@@ -51,12 +50,8 @@
   <exec_depend>std_msgs</exec_depend>
   <exec_depend>ros_acomms_msgs</exec_depend>
 
-
-
   <!-- The export tag contains other, unspecified, tags -->
   <export>
   <!-- Other tools can request additional information be placed here -->
-
   </export>
-
 </package>
diff --git a/ros_acomms/src/acomms_driver_node.py b/ros_acomms/src/acomms_driver_node.py
index 477b98b12593e7bdb86e791ea4c37e33c7c9ffcd..63c2a63f721b0c8ddbd865984cfa9a22666da918 100755
--- a/ros_acomms/src/acomms_driver_node.py
+++ b/ros_acomms/src/acomms_driver_node.py
@@ -364,7 +364,10 @@ class AcommsDriverNode(object):
         self.um.write_nmea(msg)
 
         matching_msg = None
-        remaining_time = request.timeout_ms / 1000
+        # add 1 second to ros driver timeout to handle race condition
+        # .. e.g., one of the transponders requested did not reply so the modem waits the full timeout 
+        # .. before printing the SNTTA message
+        remaining_time = (request.timeout_ms / 1000) + 1
         end_time = time() + remaining_time
 
         while remaining_time > 0:
diff --git a/ros_acomms/src/mac_utils.py b/ros_acomms/src/mac_utils.py
new file mode 100755
index 0000000000000000000000000000000000000000..b9a776e430d20849592c73b41fe0127505014935
--- /dev/null
+++ b/ros_acomms/src/mac_utils.py
@@ -0,0 +1,19 @@
+#!/usr/bin/env python3
+
+from collections import namedtuple
+FDPMaxBytes4Rate = namedtuple('FDPMaxBytes4Rate', 'rate max_bytes default packet_duration_ms')
+
+class PSK_ROS_FDP_Rates(object):
+    FDP_MAX_BYTES_FOR_MINI_RATE = [
+        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,  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/ros_acomms/src/tdma_advanced_node.py b/ros_acomms/src/tdma_advanced_node.py
new file mode 100755
index 0000000000000000000000000000000000000000..5ef960a912886f838225b678debc1aaa77ce6f2a
--- /dev/null
+++ b/ros_acomms/src/tdma_advanced_node.py
@@ -0,0 +1,332 @@
+#!/usr/bin/env python3
+
+import rospy
+from ros_acomms_msgs.srv import PingModem, PingModemRequest, PingTransponders, PingTranspondersRequest
+from ros_acomms_msgs.msg import TdmaAdvancedStatus
+from tdma_node import TdmaMacNode
+
+from ros_acomms.cfg import tdma_advancedConfig
+from dynamic_reconfigure.server import Server as DynamicReconfigureServer
+
+import datetime
+
+from mac_utils import PSK_ROS_FDP_Rates # pure python class for non-ros functionality
+
+class TdmaAdvancedMacNode(TdmaMacNode):
+    """
+    TDMA MAC node that support dynamic reconfiguration of parameters, modem and transponder pings, and software mute
+
+    Extends TdmaMacNode
+
+    Attributes:
+        nav_slots (list): A list of slot for navigation pings.
+        comms_slots (list): A list of slot numbers for comms packets.
+        software_mute (bool): A flag indicating whether the node is in software mute mode.
+        cycle_start_time_offset_sec (float): The offset in seconds for the start time of the TDMA cycle.
+        pings_per_slot (int): The number of pings per slot.
+        ping_modems (bool): A flag indicating whether to ping modems.
+        ping_modem_src (int): The source ID of the modem to ping.
+        ping_modem_timeout_sec (int): The timeout in seconds for modem pings.
+        ping_cdr (int): The Compact Data Request (see the uModem manual) parameter sent with ping requests.
+        ping_transponders (bool): A flag indicating whether to ping transponders.
+        ping_transponder_a (bool): A flag indicating whether to ping transponder A.
+        ping_transponder_b (bool): A flag indicating whether to ping transponder B.
+        ping_transponder_c (bool): A flag indicating whether to ping transponder C.
+        ping_transponder_d (bool): A flag indicating whether to ping transponder D.
+        transponder_reply_timeout_sec (int): The timeout in seconds for transponder replies.
+
+    Methods:
+        wait_for_ping_services(timeout=120)
+            Waits for the ping_modem and ping_transponders services to come online.
+
+        config_slot_mask(slot_type)
+            Calculates the slot mask based on the slot type specified.
+
+        reconfigure(config, level)
+            Updates the configuration based on dynamic reconfigure requests.
+    """
+    def __init__(self, subclass=False):
+        if not subclass:
+            rospy.init_node('tdma_advanced_mac')
+            self.tdma_status_publisher = rospy.Publisher('tdma_advanced_status', TdmaAdvancedStatus, queue_size=0)
+        super().__init__(subclass=True)
+        # take supers active_slots list of ints and generate comms_slot & nav_slots masks
+        self.nav_slots = self.config_slot_mask(slot_type=rospy.get_param('~nav_slots', None))
+        self.comms_slots = self.config_slot_mask(slot_type=rospy.get_param('~comms_slots', None))
+
+        # do advanced stuff
+        self.software_mute = rospy.get_param('~software_mute', False)
+        self.cycle_start_time_offset_sec = rospy.get_param('~skew_cycle_sec', 0)
+        self.pings_per_slot = rospy.get_param('~pings_per_slot', 0)
+        self.ping_modems = rospy.get_param('~ping_modem', bool(self.pings_per_slot))
+        self.ping_modem_src = rospy.get_param('~ping_modem_src', 1)
+        self.ping_modem_timeout_sec = rospy.get_param('~ping_modem_timeout_sec', 5)
+        self.ping_cdr = rospy.get_param('~ping_cdr', 4)
+
+        self.ping_transponders = rospy.get_param('~ping_transponders', False)
+        self.ping_transponder_a = rospy.get_param('~ping_transponder_a', True)
+        self.ping_transponder_b = rospy.get_param('~ping_transponder_b', True)
+        self.ping_transponder_c = rospy.get_param('~ping_transponder_c', True)
+        self.ping_transponder_d = rospy.get_param('~ping_transponder_d', True)
+        self.transponder_reply_timeout_sec = rospy.get_param('~transponder_reply_timeout_sec', 5)
+
+        self.wait_for_ping_services(timeout=rospy.get_param('~wait_for_services_timeout_sec', None))
+
+        if not subclass:
+            # setup dynamic reconf for periodic ping params
+            self.first_dynamic_reconf = True
+            self.reconfigure_server = DynamicReconfigureServer(tdma_advancedConfig, self.reconfigure)
+
+            rospy.loginfo("tdma_advanced_mac node running.")
+            self.spin()
+
+    def wait_for_ping_services(self, timeout=120):
+        # wait for ping_modem service to come online
+        rospy.loginfo("tdma_advanced_mac waiting for ping_modem service")
+        rospy.wait_for_service('ping_modem', timeout=timeout)
+        self.send_modem_ping = rospy.ServiceProxy('ping_modem', PingModem)
+
+        try:
+            # since the ping_modem service is available in sim and hw, it blocking waits,
+            # as of jan 2024, modem_sim does not have a ping_transponders service.
+            # if the user has ping_transponders = True and this times out, it will kill the node
+            # if the user has ping_transponders = False, we just print an error if this service times out (which it will for sim)
+            rospy.wait_for_service('ping_transponders', timeout=1)
+        except rospy.exceptions.ROSException:
+            if self.ping_transponders:
+                raise # raise error right away, otherwise, it will get thrown when user attempts to call service
+            else:
+                rospy.logwarn(f'Timed out waiting for transponder ping service. This will throw an error when user tries to ping a transponder.')
+        self.send_transponder_ping = rospy.ServiceProxy('ping_transponders', PingTransponders)
+
+    def config_slot_mask(self, slot_type):
+        if slot_type:
+            # if anything passed from constructor, non-default behavior
+            if isinstance(slot_type, int):
+                slot_type = [slot_type]
+            if isinstance(slot_type, str):
+                # if it's a string it's probably because this is a dynamic reconfigure callback
+                if len(slot_type) > 1:
+                    slot_type = [int(slot) for slot in slot_type.split(',')]
+                else:
+                    slot_type = [int(slot_type)]
+            # user passed value(s) for set of slots to allow <slot_type-traffic> in
+            slot_mask = [slot for slot in self.active_slots if slot in slot_type]
+        else:
+            # when nothing was passed for this slot type, by default, mask is allow == True
+            slot_mask = [slot for slot in self.active_slots]
+        return slot_mask
+
+    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
+            config['skew_cycle_sec'] = self.cycle_start_time_offset_sec
+            config['software_mute'] = self.software_mute
+            config['ping_modem'] = self.ping_modems
+            config['pings_per_slot'] = self.pings_per_slot
+            config['ping_modem_src'] = self.ping_modem_src
+            config['ping_modem_timeout_sec'] = self.ping_modem_timeout_sec
+            config['ping_cdr'] = self.ping_cdr
+
+            config['ping_transponders'] = self.ping_transponders  
+            config['ping_transponder_a'] = self.ping_transponder_a 
+            config['ping_transponder_b'] = self.ping_transponder_b 
+            config['ping_transponder_c'] = self.ping_transponder_c 
+            config['ping_transponder_d'] = self.ping_transponder_d 
+            
+            # The following 3 parameters with a trailing '_' are for the dynamic reconfigure interface
+            # .. since dynreconf does not support a list type, we can set active_slots with a parsed string
+            # BUT, having the same param names in the same scope with different data types throws errors
+            config['active_slots_'] = ','.join([str(slot) for slot in self.active_slots])
+            config['nav_slots_'] = ','.join([str(slot) for slot in self.nav_slots])
+            config['comms_slots_'] = ','.join([str(slot) for slot in self.comms_slots])
+
+            config['num_slots'] = self.num_slots
+            config['slot_duration_seconds'] = self.slot_duration_seconds
+            config['guard_time_seconds'] = self.guard_time_seconds
+            config['packet_length_seconds'] = self.packet_length_seconds
+            config['miniframe_rate'] = self.miniframe_rate
+            config['dataframe_rate'] = self.dataframe_rate
+            rospy.logdebug(f'First dynamic_reconfigure call, syncing config from init')
+            return config
+
+        rospy.logdebug("tdma_advanced_mac dynamic reconfigure request received.")
+        rospy.logdebug(f"config: {config}")
+
+        self.cycle_start_time_offset_sec = config['skew_cycle_sec']
+        self.setup_active_slots(
+                # always making sure to sanitize dynamic reconfigure args
+                active_slots=[int(slot) for slot in config['active_slots_'].strip(',').split(',')],
+                num_slots=int(config['num_slots']),
+                slot_duration_seconds=int(config['slot_duration_seconds']),
+                cycle_start_time=datetime.datetime.fromtimestamp(self.cycle_start_time.timestamp() + self.cycle_start_time_offset_sec),
+                guard_time_seconds=int(config['guard_time_seconds']),
+                packet_length_seconds=int(config['packet_length_seconds']),
+            )
+
+        # parse comms_slots and nav_slots from str into list of ints (no error checking on this)
+        self.comms_slots = [int(slot) for slot in config['comms_slots_'].strip(',').split(',')]
+        self.nav_slots = [int(slot) for slot in config['nav_slots_'].strip(',').split(',')]
+
+        self.software_mute = config['software_mute']
+
+        self.ping_modems = config['ping_modem']
+        self.ping_modem_src = config['ping_modem_src']
+        self.pings_per_slot = config['pings_per_slot']
+        self.ping_cdr = config['ping_cdr']
+        self.ping_modem_timeout_sec = config['ping_modem_timeout_sec'] 
+
+        self.ping_transponders = config['ping_transponders'] 
+        self.ping_transponder_a = config['ping_transponder_a']
+        self.ping_transponder_b = config['ping_transponder_b']
+        self.ping_transponder_c = config['ping_transponder_c']
+        self.ping_transponder_d = config['ping_transponder_d']
+
+        # update derived param cycle_duration in super
+        self.cycle_duration = self.num_slots * self.slot_duration_seconds
+
+        miniframe_rate, maximum_miniframe_bytes = self.miniframe_rate, self.maximum_miniframe_bytes
+        if self.miniframe_rate != config['miniframe_rate']:
+            miniframe_rate = config['miniframe_rate']
+            maximum_miniframe_bytes = PSK_ROS_FDP_Rates.FDP_MAX_BYTES_FOR_MINI_RATE[miniframe_rate].default
+
+        dataframe_rate, maximum_dataframe_bytes = self.dataframe_rate, self.maximum_dataframe_bytes
+        if self.dataframe_rate != config['dataframe_rate']:
+            dataframe_rate = config['dataframe_rate']
+            maximum_dataframe_bytes = PSK_ROS_FDP_Rates.FDP_MAX_BYTES_FOR_DATA_RATE[dataframe_rate].default
+
+        self.set_frame_rate(
+                miniframe_rate=miniframe_rate,
+                dataframe_rate=dataframe_rate,
+                maximum_miniframe_bytes=maximum_miniframe_bytes,
+                maximum_dataframe_bytes=maximum_dataframe_bytes,
+            )
+
+        return config
+
+    def generate_tdma_advanced_status(self, basic_msg):
+        msg = TdmaAdvancedStatus()
+        msg.software_mute = self.software_mute
+        msg.message = ''
+
+        msg.miniframe_rate = self.miniframe_rate
+        msg.dataframe_rate = self.dataframe_rate
+        msg.maximum_dataframe_bytes = self.maximum_dataframe_bytes
+        msg.maximum_miniframe_bytes = self.maximum_miniframe_bytes
+        msg.num_slots = self.num_slots
+        # TODO, this only shows the first slot in the list, since that's the most common case,
+        # .. we should come up with a nicer way to describe active slots when more than one is passed
+        msg.active_slots = self.active_slots[0]
+        msg.nav_slots = self.nav_slots[0]
+        msg.comms_slots = self.comms_slots[0]
+
+        msg.pings_per_slot = self.pings_per_slot if self.ping_modems else 0
+        msg.ping_modem_src = self.ping_modem_src
+        msg.ping_transponders = self.ping_transponders
+
+        msg.tdma_basic_status = basic_msg
+        return msg
+
+    def handle_queuing_packet(self, current_slot, remaining_active_seconds, sent_modem_pings, sent_transponder_ping):
+        # we are active and have atleast enough time to send another packet
+        # if we are allowed to do nav pings in this slot, handle that first
+        nav_ping_duration_sec = 0
+        update_last_tx = False
+
+        if current_slot in self.nav_slots and (not sent_modem_pings or not sent_transponder_ping):
+            # in active slot with nav pings allowed
+            sent_modem_pings, sent_transponder_ping, nav_ping_duration_sec = self.send_nav_ping(remaining_active_seconds, sent_modem_pings, sent_transponder_ping)
+
+        if nav_ping_duration_sec > 0:
+            # sent nav pings, return
+            update_last_tx = True
+            return sent_modem_pings, sent_transponder_ping, update_last_tx
+
+        if current_slot in self.comms_slots:
+            # check and make sure comms are allowed this slot
+            # no nav pings sent this iter, comms allowed, go ahead with packet
+            position_in_queue = self.send_next_packet()
+            update_last_tx = True
+            # after sending comms packet, we clear the flags on nav pings
+            # after sending all modem pings requested, a transponder ping (if requested) is sent out, 
+            # .. then comms are allowed to use the remaining active time
+            sent_modem_pings, sent_transponder_ping = False, False
+            rospy.logdebug(f'tdma advanced sent packet, position in queue: {position_in_queue}')
+            
+        return sent_modem_pings, sent_transponder_ping, update_last_tx
+
+    def spin(self):
+        rate = rospy.Rate(5)
+        last_tx_time = 0
+        msg = None
+        sent_modem_pings = False
+        sent_transponder_ping = False
+
+        while not rospy.is_shutdown():
+            msg = self.get_current_slot_info(software_mute=self.software_mute)
+            self.tdma_status_publisher.publish(self.generate_tdma_advanced_status(basic_msg=msg))
+
+            if self.can_transmit_now(msg=msg, last_tx_time=last_tx_time):
+                # we are active and have atleast enough time to send another packet
+                sent_modem_pings, sent_transponder_ping, update_last_tx = self.handle_queuing_packet(
+                        msg.current_slot,
+                        msg.remaining_active_seconds,
+                        sent_modem_pings, 
+                        sent_transponder_ping
+                    )
+                if update_last_tx:
+                    last_tx_time = rospy.get_time()
+                else:
+                    # nothing sent, sleep then check again
+                    rate.sleep()
+                    continue
+            else:
+                # not enough time. sleep for rate and try again
+                rate.sleep()
+                continue
+
+    def send_nav_ping(self, remaining_active_seconds, sent_modem_pings, sent_transponder_ping):
+        nav_ping_duration_sec = 0
+        if self.ping_modems and not sent_modem_pings:
+            # fire off the modem pings
+            start_t = rospy.get_time()
+            for i in range(self.pings_per_slot):
+                # before sending ping, make sure we have enough time remaining
+                nav_ping_duration_sec = rospy.get_time() - start_t
+                remaining_time = remaining_active_seconds - nav_ping_duration_sec
+                if remaining_time < self.ping_modem_timeout_sec:
+                    rospy.logwarn(f'Not enough time to send another ping with remaining time: {remaining_time}s. Cancelled ping [{i + 1}/{self.pings_per_slot}]')
+                    break
+
+                req = PingModemRequest(dest=self.ping_modem_src, rate=self.miniframe_rate, cdr=self.ping_cdr, hexdata=bytes(), reply_timeout=self.ping_modem_timeout_sec)
+                rospy.loginfo(f'[{i + 1}/{self.pings_per_slot}]: Sending TWTT ping to modem_src: {self.ping_modem_src}, request:\n{req}')
+                resp = self.send_modem_ping(req)
+                rospy.loginfo(f'Response from send_modem_ping:\n{resp}')
+
+            sent_modem_pings = True
+            nav_ping_duration_sec = rospy.get_time() - start_t
+        elif self.ping_transponders and not sent_transponder_ping:
+            # fire off transponder ping
+            start_t = rospy.get_time()
+
+            req = PingTranspondersRequest(transponder_dest_mask=[self.ping_transponder_a, self.ping_transponder_b, self.ping_transponder_c, self.ping_transponder_d], timeout_ms=self.transponder_reply_timeout_sec * 1000)
+            rospy.loginfo(f"Sending transponder ping, request:\n{req}")
+            resp = self.send_transponder_ping(req)
+            rospy.loginfo(f"Sent transponder ping. Response:\n{resp}")
+            sent_transponder_ping = True
+            nav_ping_duration_sec = rospy.get_time() - start_t
+
+        return sent_modem_pings, sent_transponder_ping, nav_ping_duration_sec
+
+if __name__ == "__main__":
+    try:
+        tdma_state_node = TdmaAdvancedMacNode()
+
+    except rospy.ROSInterruptException:
+        rospy.loginfo("tdma_node shutdown (interrupt)")
+
+
diff --git a/ros_acomms/src/tdma_nav_header_node.py b/ros_acomms/src/tdma_nav_header_node.py
deleted file mode 100755
index c3eefec6fe8c1a3a4fd7ff95c91384e817d2b81d..0000000000000000000000000000000000000000
--- a/ros_acomms/src/tdma_nav_header_node.py
+++ /dev/null
@@ -1,264 +0,0 @@
-#!/usr/bin/env python3
-
-import rospy
-
-from ros_acomms_msgs.srv import PingModem, PingTransponders
-from ros_acomms_msgs.msg import TdmaNavStatus
-from dynamic_reconfigure.server import Server as DynamicReconfigureServer
-from ros_acomms.cfg import tdma_nav_headerConfig
-
-from tdma_node import TdmaMacNode
-
-class TdmaNavHeaderMacNode(TdmaMacNode):
-    def __init__(self):
-        rospy.init_node('tdma_nav_header_mac')
-        super().__init__(subclass=True)
-
-        self.tdma_status_publisher = rospy.Publisher('tdma_nav_status', TdmaNavStatus, queue_size=10)
-
-        # get duration of tdma slot to dedicate to nav messages
-        self.nav_duration_seconds = rospy.get_param('~nav_duration_seconds', 15)
-        self.nav_guard_time_seconds = rospy.get_param('~nav_guard_time_seconds', 5)
-        self.ping_hex_data = rospy.get_param('~ping_hex_data', '')
-        if self.ping_hex_data == '':
-            self.ping_hex_data = bytes()
-        else:
-            self.ping_hex_data = bytes(self.ping_hex_data)
-        # ping CDR field
-        self.ping_cdr = int(rospy.get_param('~ping_cdr', '0x04'), base=16) # CDR field request in PNG iso style datetime 
-                                                                           # ..representing TOT from remote. the datetime is
-                                                                           # ..embedding in PNR ping reply. See FDP spec for other
-                                                                           # ..CDR values
-        # params for nav header pinging that happens during the nav portion of every tdma cycle
-        self.transponder_A = rospy.get_param('~transponder_A', True)
-        self.transponder_B = rospy.get_param('~transponder_B', True)
-        self.transponder_C = rospy.get_param('~transponder_C', True)
-        self.transponder_D = rospy.get_param('~transponder_D', True)
-        self.transponder_reply_timeout_ms = rospy.get_param('~transponder_reply_timeout_ms', 5000)
-        self.ping_dest_id = rospy.get_param('~ping_dest_id', 121)
-        self.ping_rate = rospy.get_param('~ping_rate', 1)
-        # cycle through rates 1,3,5 every n pings, 0 means use set rate don't change
-        self.cycle_rate_every_n_pings = rospy.get_param('~cycle_rate_every_n_pings', 0)
-        self.cycles_at_rate = 0
-        self.ping_modem_on = rospy.get_param('~ping_modem_on', True)
-        self.ping_transponders_on = rospy.get_param('~ping_transponders_on', False)
-
-        # wait for ping_modem service to come online
-        rospy.loginfo("tdma_nav_header_mac waiting for ping_modem service")
-        rospy.wait_for_service('ping_modem')
-        self.send_modem_ping = rospy.ServiceProxy('ping_modem', PingModem)
-
-        # wait for ping_transponder service to come online
-        rospy.loginfo("tdma_nav_header_mac waiting for ping_transponders service")
-        rospy.wait_for_service('ping_transponders')
-        self.send_transponder_ping = rospy.ServiceProxy('ping_transponders', PingTransponders)
-
-        # setup dynamic reconf for periodic ping params
-        self.first_dynamic_reconf = True
-        self.reconfigure_server = DynamicReconfigureServer(tdma_nav_headerConfig, self.reconfigure)
-        
-        self.non_nav_slot_duration = self.slot_duration_seconds - self.nav_duration_seconds
-        rospy.loginfo("tdma_nav_header_mac running")
-        self.spin()
-
-    def transponder_dest_mask(self, as_list=True):
-        if as_list:
-            return [self.transponder_A,
-                    self.transponder_B,
-                    self.transponder_C,
-                    self.transponder_D,]
-        return '{}{}{}{}'.format(
-                self.transponder_A,
-                self.transponder_B,
-                self.transponder_C,
-                self.transponder_D,
-            )
-
-    @property
-    def rate(self):
-        if self.cycle_rate_every_n_pings > 0:
-            if self.cycles_at_rate == self.cycle_rate_every_n_pings:
-                self.cycles_at_rate = 0
-                # ready to cycle to next rate for this ping
-                if self.ping_rate != 5:
-                    self.ping_rate += 2
-                else:
-                    self.ping_rate = 1
-            else:
-                self.cycles_at_rate += 1
-
-        return self.ping_rate
-
-    @property
-    def tdma_nav_mode(self):
-        tdma_nav_mode_str = ""
-        if self.ping_modem_on:
-            tdma_nav_mode_str += f"PingModem:dest:{self.ping_dest_id},rate:{self.ping_rate},"
-        if self.ping_transponders_on:
-            tdma_nav_mode_str += f"PingTransponders:transponder_dest_mask:{self.transponder_dest_mask()}"
-        if not self.ping_modem_on and not self.ping_transponders_on:
-            # no nav portion whole slot can be used now until ping modem/transponder turned back on
-            tdma_nav_mode_str += "no-pings-requested"
-        return tdma_nav_mode_str
-
-    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
-            config['nav_duration_seconds'] = self.nav_duration_seconds
-            config['nav_guard_time_seconds'] = self.nav_guard_time_seconds
-
-            config['transponder_A'] = self.transponder_A
-            config['transponder_B'] = self.transponder_B
-            config['transponder_C'] = self.transponder_C
-            config['transponder_D'] = self.transponder_D
-            config['transponder_reply_timeout_ms'] = self.transponder_reply_timeout_ms
-
-            config['ping_dest_id'] = self.ping_dest_id
-            config['ping_rate'] = self.ping_rate
-            config['cycle_rate_every_n_pings'] = self.cycle_rate_every_n_pings
-            config['ping_cdr'] = int(str(self.ping_cdr), base=16)
-            config['ping_hex_data'] = self.ping_hex_data
-
-            config['ping_modem_on'] = self.ping_modem_on
-            config['ping_transponders_on'] = self.ping_transponders_on
-            rospy.loginfo(f'First dynamic_reconfigure call, syncing config from init')
-            return config
-
-        rospy.loginfo("tdma_nav_header_mac driver reconfigure request received.")
-        rospy.loginfo(f"config: {config}")
-
-        self.nav_duration_seconds = config['nav_duration_seconds']
-        self.nav_guard_time_seconds = config['nav_guard_time_seconds']
-
-        self.transponder_A = config['transponder_A']
-        self.transponder_B = config['transponder_B']
-        self.transponder_C = config['transponder_C']
-        self.transponder_D = config['transponder_D']
-        self.transponder_reply_timeout_ms = config['transponder_reply_timeout_ms']
-
-        self.ping_dest_id = config['ping_dest_id']
-        self.ping_rate = config['ping_rate']
-        self.cycle_rate_every_n_pings = config['cycle_rate_every_n_pings']
-        self.ping_cdr = int(str(config['ping_cdr']), base=16)
-        self.ping_hex_data = config['ping_hex_data']
-        if self.ping_hex_data == '':
-            self.ping_hex_data = bytes()
-        else:
-            self.ping_hex_data = bytes(self.ping_hex_data)
-
-        self.ping_modem_on = config['ping_modem_on']
-        self.ping_transponders_on = config['ping_transponders_on']
-
-        return config
-
-    def get_current_slot_info(self):
-        now_secs = rospy.Time.now().to_sec()
-        offset_secs = now_secs - self.cycle_start_secs
-        in_cycle_secs = offset_secs % self.cycle_duration
-        current_slot = int(in_cycle_secs // self.slot_duration_seconds)
-        we_are_active = self.slots[current_slot]['active']
-        remaining_slot_seconds = self.slot_duration_seconds - (in_cycle_secs % self.slot_duration_seconds)
-        # handle the case where we are active in subsequent slots
-        remaining_active_seconds = remaining_slot_seconds
-        for i in range(current_slot + 1, current_slot+self.num_slots):
-            next_slot_num = i % self.num_slots
-            if self.slots[next_slot_num]['active']:
-                remaining_active_seconds += self.slot_duration_seconds
-            else:
-                break    
-
-        # Figure out if we're in nav_portion of slot
-        is_nav_portion = False
-        # Figure out how many seconds remain until we go active
-        if we_are_active:
-            time_to_next_active = 0
-            if remaining_active_seconds - self.nav_guard_time_seconds > self.non_nav_slot_duration:
-                is_nav_portion = True
-        else:
-            time_to_next_active = remaining_slot_seconds
-            for i in range(current_slot + 1, current_slot + self.num_slots):
-                next_slot_num = i % self.num_slots
-                if not self.slots[next_slot_num]['active']:
-                    time_to_next_active += self.slot_duration_seconds
-                else:
-                    break
-
-        # every time we update this, publish the current status.  This may need to move if we ever start
-        # calling this function quickly
-        remaining_nav_seconds = remaining_active_seconds - self.non_nav_slot_duration if is_nav_portion else 0.0
-        msg = TdmaNavStatus(
-            is_nav_portion=is_nav_portion,
-            we_are_active=we_are_active, 
-            current_slot=current_slot,
-            remaining_nav_seconds=remaining_nav_seconds,
-            remaining_slot_seconds=remaining_slot_seconds,
-            remaining_active_seconds=remaining_active_seconds,
-            time_to_next_active=time_to_next_active,
-            tdma_nav_mode=self.tdma_nav_mode,
-            )
-        msg.header.stamp = rospy.Time.now()
-        self.tdma_status_publisher.publish(msg)
-
-        return is_nav_portion, we_are_active, current_slot, remaining_slot_seconds, remaining_active_seconds, remaining_nav_seconds, time_to_next_active
-
-    def spin(self):
-        rate = rospy.Rate(5)
-        last_tx_time = 0
-        while not rospy.is_shutdown():
-            is_nav_portion, we_are_active, current_slot, remaining_slot_seconds, remaining_active_seconds, remaining_nav_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
-
-            # if we're in the nav portion and have pings to send..
-            # else, use rest of time for data packets
-            if is_nav_portion and (self.ping_modem_on or self.ping_transponders_on):
-                self.send_next_nav_packet(timeout=remaining_nav_seconds)
-            else:
-                self.send_next_packet()
-
-            last_tx_time = rospy.get_time()
-
-    def send_next_nav_packet(self, timeout):
-        start_t = rospy.get_time()
-        if self.ping_modem_on:
-            # make service call and wait for reply
-            rate = self.rate
-            rospy.logwarn(f"Sending nav ping to dest id:{self.ping_dest_id},rate:{rate},cdr:{self.ping_cdr},hex_data:{self.ping_hex_data}")
-            resp = self.send_modem_ping(self.ping_dest_id, rate, self.ping_cdr, self.ping_hex_data, timeout)
-            stop_t = rospy.get_time()
-            timeout -= stop_t - start_t
-            rospy.loginfo(f"Sent ping and got reply with {timeout} seconds remaining in nav portion of tdma slot. Response: {resp}")
-        if self.ping_transponders_on:
-            # make service call and wait for reply
-            rospy.loginfo(f"Sending transponder ping. Mask: {self.transponder_dest_mask()}, timeout_ms: {self.transponder_reply_timeout_ms}")
-            resp = self.send_transponder_ping(transponder_dest_mask=self.transponder_dest_mask(), timeout_ms=self.transponder_reply_timeout_ms)
-            stop_t = rospy.get_time()
-            timeout -= stop_t - start_t
-            rospy.loginfo(f"Sent transponder ping and got reply with {timeout} seconds remaining in nav portion of tdma slot. Response: {resp}")
-
-if __name__ == "__main__":
-    try:
-        tdma_state_node = TdmaNavHeaderMacNode()
-
-    except rospy.ROSInterruptException:
-        rospy.loginfo("tdma_nav_header_node shutdown (interrupt)")
-
-
diff --git a/ros_acomms/src/tdma_node.py b/ros_acomms/src/tdma_node.py
index 8795085a693e81c98244cc776ff7c2115eea97f9..27c63e61f74d3727770d57b6110ca6e25e066296 100755
--- a/ros_acomms/src/tdma_node.py
+++ b/ros_acomms/src/tdma_node.py
@@ -5,70 +5,127 @@ from std_msgs.msg import Header
 from ros_acomms_msgs.srv import QueueTxPacket, QueueTxPacketRequest
 from ros_acomms_msgs.srv import GetNextPacketData
 from ros_acomms_msgs.msg import Packet, TdmaStatus
-import struct
 import datetime
 import dateutil.parser
 
-from collections import namedtuple
-FDPMaxBytes4Rate = namedtuple('FDPMaxBytes4Rate', 'rate max_bytes default packet_duration_ms')
+from mac_utils import PSK_ROS_FDP_Rates # pure python class for non-ros functionality
 
 class TdmaMacNode(object):
-    FDP_MAX_BYTES_FOR_MINI_RATE = [
-        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,  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,
-    ]
-
     def __init__(self, subclass=False):
         if not subclass:
             rospy.init_node('tdma_mac')
-            self.tdma_status_publisher = rospy.Publisher('tdma_status', TdmaStatus, queue_size=10)
-
-        self.num_slots = rospy.get_param('~num_slots', 4)
-        self.slot_duration_seconds = rospy.get_param('~slot_duration_seconds', 30)
-        self.cycle_start_time = dateutil.parser.parse(rospy.get_param('~cycle_start_time', '2020-08-05T00:00:00Z'))
-        self.setup_slot_configuration(rospy.get_param('~active_slots', 0))
-        self.guard_time_seconds = rospy.get_param('~guard_time_seconds', 5)
-        self.packet_length_seconds = rospy.get_param('~packet_length_seconds', 5) # TODO: retrieve this from the queue
-        self.always_send_test_data = rospy.get_param('~always_send_test_data', False)
-
-        self.miniframe_rate = rospy.get_param('~miniframe_rate', 1)
-        self.dataframe_rate = rospy.get_param('~dataframe_rate', 5)
-        self.maximum_miniframe_bytes = rospy.get_param(
-            '~maximum_miniframe_bytes', 
-            TdmaMacNode.FDP_MAX_BYTES_FOR_MINI_RATE[self.miniframe_rate].default if TdmaMacNode.FDP_MAX_BYTES_FOR_MINI_RATE[self.miniframe_rate] else None,
+            self.tdma_status_publisher = rospy.Publisher('tdma_status', TdmaStatus, queue_size=3)
+
+        self.setup_active_slots(
+                active_slots=rospy.get_param('~active_slots', 0), # active_slots: (int)/[int,int,..] turns this param into list of ints, slots we're active in
+                num_slots=rospy.get_param('~num_slots', 4),
+                slot_duration_seconds=rospy.get_param('~slot_duration_seconds', 30),
+                cycle_start_time=dateutil.parser.parse(rospy.get_param('~cycle_start_time', '2024-01-01T00:00:00Z')),
+                guard_time_seconds=rospy.get_param('~guard_time_seconds', 5),
+                packet_length_seconds=rospy.get_param('~packet_length_seconds', 5),
+                always_send_test_data=rospy.get_param('~always_send_test_data', False)
             )
-        self.maximum_dataframe_bytes = rospy.get_param(
-            '~maximum_dataframe_bytes', 
-            TdmaMacNode.FDP_MAX_BYTES_FOR_DATA_RATE[self.dataframe_rate].default if TdmaMacNode.FDP_MAX_BYTES_FOR_DATA_RATE[self.dataframe_rate] else None,
+
+        self.set_frame_rate(
+                miniframe_rate=rospy.get_param('~miniframe_rate', 1),
+                dataframe_rate=rospy.get_param('~dataframe_rate', 5),
+                maximum_miniframe_bytes=rospy.get_param('~maximum_miniframe_bytes', None),
+                maximum_dataframe_bytes=rospy.get_param('~maximum_dataframe_bytes', None),
             )
 
-        self.cycle_duration = self.num_slots * self.slot_duration_seconds
-        self.cycle_start_secs = self.cycle_start_time.timestamp()
+        self.wait_for_services(timeout=rospy.get_param('~wait_for_services_timeout_sec', None))
+
+        # IF CATXF messages are on, Use CATXF timestamp to signal when we are done transmitting
+        rospy.Subscriber('txf', Header, self.on_txf)
+        self.last_txf_time = rospy.get_time()
 
+        if not subclass:
+            rospy.loginfo("tdma_mac node running.")
+            self.spin()
+
+    def wait_for_services(self, timeout=120):
         rospy.loginfo("tdma waiting for queue_tx_packet service")
-        rospy.wait_for_service('queue_tx_packet')
+        rospy.wait_for_service('queue_tx_packet', timeout=timeout)
         self.queue_tx_packet = rospy.ServiceProxy('queue_tx_packet', QueueTxPacket)
 
         rospy.loginfo("tdma waiting for get_next_packet_data service")
-        rospy.wait_for_service('get_next_packet_data')
+        rospy.wait_for_service('get_next_packet_data', timeout=timeout)
         self.get_next_packet_data = rospy.ServiceProxy('get_next_packet_data', GetNextPacketData)
 
-        # Optionally, use CATXF messages to know when we are done transmitting
-        rospy.Subscriber('txf', Header, self.on_txf)
-        self.last_txf_time = rospy.get_time()
+    def setup_active_slots(self, active_slots=None,
+                                 num_slots=None,
+                                 slot_duration_seconds=None,
+                                 cycle_start_time=None,
+                                 guard_time_seconds=None,
+                                 packet_length_seconds=None,
+                                 always_send_test_data=None):
+        # update value if not None
+        if active_slots != None:
+            # TODO error handling on invalid active slot for num_slots
+            # active_slots can be a single int or list of ints
+            if isinstance(active_slots, int):
+                # could get single int for active slots from ros_params
+                self.active_slots = [active_slots]
+            elif isinstance(active_slots, list):
+                # could get list of ints for active slots from ros_params
+                self.active_slots = [int(slot) for slot in active_slots]
+            else:
+                err = f'Error with passed active_slots type! active_slots must be a single integer, list of integers or, a comma separated string of integers. active_slots: {active_slots}'
+                rospy.logerr(err)
+                raise TypeError(err)
 
-        if not subclass:
-            rospy.loginfo("tdma_mac node running.")
-            self.spin()
+        # set/update num_slots before checking if config is valid
+        self.num_slots = num_slots or self.num_slots
+
+        # make sure none of the active_slots are greater than the highest valid slot (num_slots - 1)
+        invalid_active_slots = [slot for slot in self.active_slots if slot > self.num_slots - 1]
+        if invalid_active_slots:
+            err = f'Invalid active_slots. out of bounds of num_slots. offending slots: {invalid_active_slots}. active_slots are zero-indexed. The highest/last valid slot is: {self.num_slots - 1}'
+            rospy.logerr(err)
+            raise AttributeError(err)
+
+        if guard_time_seconds == 0:
+            # TODO: is 0 ever an O.K. value to set, for any reason?
+            self.guard_time_seconds = guard_time_seconds
+        else:
+            self.guard_time_seconds = guard_time_seconds or self.guard_time_seconds
+
+        if packet_length_seconds == 0:
+            # TODO: is 0 ever an O.K. value to set, for any reason?
+            # .. maybe if we were using last_txf?
+            self.packet_length_seconds = packet_length_seconds
+        else:
+            self.packet_length_seconds = packet_length_seconds or self.packet_length_seconds
+
+        if always_send_test_data != None:
+            self.always_send_test_data = bool(always_send_test_data)
+
+        self.slot_duration_seconds = slot_duration_seconds or self.slot_duration_seconds
+        self.cycle_start_time = cycle_start_time or self.cycle_start_time
+        self.cycle_duration = self.num_slots * self.slot_duration_seconds
+        self.cycle_start_secs = self.cycle_start_time.timestamp()
+
+        # slot dict lookup, we check this as a step in determining if we are active
+        self.slots = [{'active': i in self.active_slots} for i in range(self.num_slots)]
+
+    def set_frame_rate(self, miniframe_rate=None,
+                             dataframe_rate=None,
+                             maximum_miniframe_bytes=None,
+                             maximum_dataframe_bytes=None):
+        # update value if not None
+        self.miniframe_rate = miniframe_rate or self.miniframe_rate
+        self.dataframe_rate = dataframe_rate or self.dataframe_rate
+
+        # update value when valid. if, invalid, gets set to default for the rate
+        if hasattr(self, 'maximum_miniframe_bytes'):
+            self.maximum_miniframe_bytes = maximum_miniframe_bytes or self.maximum_miniframe_bytes
+        else:
+            self.maximum_miniframe_bytes = maximum_miniframe_bytes or PSK_ROS_FDP_Rates.FDP_MAX_BYTES_FOR_MINI_RATE[self.miniframe_rate].default
+
+        if hasattr(self, 'maximum_dataframe_bytes'):
+            self.maximum_dataframe_bytes = maximum_dataframe_bytes or self.maximum_dataframe_bytes
+        else:
+            self.maximum_dataframe_bytes = maximum_dataframe_bytes or PSK_ROS_FDP_Rates.FDP_MAX_BYTES_FOR_DATA_RATE[self.dataframe_rate].default
 
     def get_valid_max_bytes_for_rate(self, rate, req_max_bytes, dataframe=True):
         if req_max_bytes is None:
@@ -86,9 +143,9 @@ class TdmaMacNode(object):
         # .. sets rosparam for maximum_dataframe_bytes|maximum_miniframe_bytes if value passed was too large
         #
         if dataframe:
-            fdp_max_bytes_4_rate = TdmaMacNode.FDP_MAX_BYTES_FOR_DATA_RATE[rate]
+            fdp_max_bytes_4_rate = PSK_ROS_FDP_Rates.FDP_MAX_BYTES_FOR_DATA_RATE[rate]
         else:
-            fdp_max_bytes_4_rate = TdmaMacNode.FDP_MAX_BYTES_FOR_MINI_RATE[rate]
+            fdp_max_bytes_4_rate = PSK_ROS_FDP_Rates.FDP_MAX_BYTES_FOR_MINI_RATE[rate]
 
         if fdp_max_bytes_4_rate and req_max_bytes > fdp_max_bytes_4_rate.max_bytes:
             err = f'Cannot send a {req_max_bytes} byte '
@@ -126,99 +183,88 @@ class TdmaMacNode(object):
         # Reset our "time since last TX done" timer (used with guard time)
         self.last_txf_time = msg.stamp.to_sec()
 
-    def setup_slot_configuration(self, active_slots_param):
-        # Accept single integers or lists
-        if type(active_slots_param) is int:
-            active_slots_param = [active_slots_param]
-        if type(active_slots_param) is list:
-            # Convert it to a dict
-            active_slots_param = dict.fromkeys(active_slots_param, {})
-        # Check to make sure that this all makes sense
-        if max(active_slots_param.keys()) > (self.num_slots - 1):
-            rospy.logerr(
-                "Invalid setting for active_slots.  num_slots={}, so the highest slot number is {} (zero-based indexing)".format(
-                    self.num_slots, self.num_slots - 1))
-            exit()
-        self.slots = {}
-        for i in range(self.num_slots):
-            self.slots[i] = {}
-            try:
-                this_slot = active_slots_param[i]
-                self.slots[i]['allow_nav'] = this_slot.get('allow_nav', True)
-                self.slots[i]['allow_comms'] = this_slot.get('allow_comms', True)
-                self.slots[i]['shared_priority'] = this_slot.get('shared_priority', False)
-                self.slots[i]['duplex'] = this_slot.get('duplex', False)
-                self.slots[i]['active'] = True
-            except KeyError:
-                # mark it as disabled
-                self.slots[i] = {'active': False}
-
-
-    def get_current_slot_info(self):
+    def get_current_slot(self):
         now_secs = rospy.Time.now().to_sec()
         offset_secs = now_secs - self.cycle_start_secs
         in_cycle_secs = offset_secs % self.cycle_duration
-        current_slot = int(in_cycle_secs // self.slot_duration_seconds)
-        we_are_active = self.slots[current_slot]['active']
         remaining_slot_seconds = self.slot_duration_seconds - (in_cycle_secs % self.slot_duration_seconds)
-        # handle the case where we are active in subsequent slots
-        remaining_active_seconds = remaining_slot_seconds
-        for i in range(current_slot + 1, current_slot+self.num_slots):
-            next_slot_num = i % self.num_slots
-            if self.slots[next_slot_num]['active']:
-                remaining_active_seconds += self.slot_duration_seconds
-            else:
-                break
 
-        # Figure out how many seconds remain until we go active
+        current_slot = int(in_cycle_secs // self.slot_duration_seconds)
+        return current_slot, remaining_slot_seconds
+
+    def get_current_slot_info(self, software_mute=False):
+        current_slot, remaining_slot_seconds = self.get_current_slot()
+        we_are_active = self.slots[current_slot]['active'] and not software_mute
+        
         if we_are_active:
             time_to_next_active = 0
+            remaining_active_seconds = remaining_slot_seconds
         else:
+            remaining_active_seconds = 0
+            # Figure out how many seconds remain until we go active
             time_to_next_active = remaining_slot_seconds
-            for i in range(current_slot + 1, current_slot + self.num_slots):
-                next_slot_num = i % self.num_slots
-                if not self.slots[next_slot_num]['active']:
+            # plus any slot after this current one that isn't our active slot
+            next_slot = current_slot + 1
+
+            for _ in range(self.num_slots):
+                # handle wrap around
+                if next_slot >= self.num_slots: next_slot = 0 # wrapped around
+                # add self.slot_duration_seconds for each slot that isn't our active slot between now and 
+                # .. next active slot. break when we hit our active slot
+                if next_slot not in self.active_slots:
                     time_to_next_active += self.slot_duration_seconds
+                    next_slot += 1
                 else:
                     break
 
-        # every time we update this, publish the current status.  This may need to move if we ever start
-        # calling this function quickly
-        msg = TdmaStatus(we_are_active=we_are_active, current_slot=current_slot,
-                         remaining_slot_seconds=remaining_slot_seconds,
-                         remaining_active_seconds=remaining_active_seconds,
-                         time_to_next_active=time_to_next_active)
+        # populate a TdmaStatus ROS msg, to be published in spin
+        msg = TdmaStatus(
+                we_are_active=we_are_active, 
+                current_slot=current_slot,
+                remaining_slot_seconds=remaining_slot_seconds,
+                remaining_active_seconds=remaining_active_seconds,
+                time_to_next_active=time_to_next_active
+            )
         msg.header.stamp = rospy.Time.now()
-        self.tdma_status_publisher.publish(msg)
 
-        return we_are_active, current_slot, remaining_slot_seconds, remaining_active_seconds, time_to_next_active
+        return msg
+
+    def can_transmit_now(self, msg, last_tx_time):
+        if not msg.we_are_active:
+            return False
+        if msg.remaining_active_seconds < (self.guard_time_seconds + self.packet_length_seconds):
+            # not enough time remaining in active slot for another packet transmit
+            return False
+
+        current_time = rospy.get_time()
+        # check current_time with last_tx_time (tdma queued a packet in spin) + padding
+        if current_time <= (last_tx_time + self.guard_time_seconds + self.packet_length_seconds) or \
+           current_time <= last_tx_time + self.guard_time_seconds:
+            # still too soon to transmit after previous tx, software lockout w/ guard_time_seconds
+            return False
+
+        return True
 
     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
+        msg = None
 
-            # 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:
+        while not rospy.is_shutdown():
+            msg = self.get_current_slot_info()
+            self.tdma_status_publisher.publish(msg)
+
+            if self.can_transmit_now(msg=msg, last_tx_time=last_tx_time):
+                # we are active and have atleast enough time to send another packet
+                position_in_queue = self.send_next_packet()
+                last_tx_time = rospy.get_time()
+                rospy.logdebug(f'tdma sent packet @ {last_tx_time}, position in queue: {position_in_queue}')
+            else:
+                # not enough time. sleep for rate and try again
                 rate.sleep()
                 continue
 
-            self.send_next_packet()
-            last_tx_time = rospy.get_time()
-
-    def send_next_packet(self):
+    def send_next_packet(self, insert_at_head=False):
         # TODO: handle other packet sizes
         packet_data_response = self.get_next_packet_data(num_miniframe_bytes=self.maximum_miniframe_bytes,
                                                          num_dataframe_bytes=self.maximum_dataframe_bytes)
@@ -239,18 +285,20 @@ class TdmaMacNode(object):
         queue_packet.miniframe_bytes = packet_data_response.miniframe_bytes
         queue_packet.dataframe_bytes = packet_data_response.dataframe_bytes
 
-        req = QueueTxPacketRequest(insert_at_head=False,
+        req = QueueTxPacketRequest(insert_at_head=insert_at_head,
                                    packet=queue_packet)
 
         resp = self.queue_tx_packet(req)
-        return
+        return resp.position_in_queue
 
 
 if __name__ == "__main__":
+    import traceback
     try:
         tdma_state_node = TdmaMacNode()
 
     except rospy.ROSInterruptException:
         rospy.loginfo("tdma_node shutdown (interrupt)")
 
-
+    except:
+        rospy.loginfo(f"tdma_node shutdown. Thrown unhandled exception: {traceback.format_exc()}")
diff --git a/ros_acomms/src/tdma_scripted_node.py b/ros_acomms/src/tdma_scripted_node.py
new file mode 100755
index 0000000000000000000000000000000000000000..aebecb82a11991e24475a1a5a0d86a88eb8a77b9
--- /dev/null
+++ b/ros_acomms/src/tdma_scripted_node.py
@@ -0,0 +1,193 @@
+#!/usr/bin/env python3
+
+import rospy
+from ros_acomms_msgs.msg import TdmaScriptedStatus
+from tdma_advanced_node import TdmaAdvancedMacNode
+
+# from ros_acomms.cfg import tdma_scriptedConfig
+from ros_acomms.cfg import tdma_advancedConfig
+from dynamic_reconfigure.server import Server as DynamicReconfigureServer
+
+from mac_utils import FDPMaxBytes4Rate, PSK_ROS_FDP_Rates # pure python class for non-ros functionality
+
+class TdmaScriptedMacNode(TdmaAdvancedMacNode):
+    """
+    An advanced TDMA MAC node that can execute a scripted test plan.
+
+    Inherits from TdmaAdvancedMacNode.
+
+    Attributes:
+    - scripted_test_plan (dict): The scripted test plan.
+    - override_test_plan_packet_duration (bool): Indicates whether to use the packet duration passed to the node or the value in scripted_test_plan.
+    - tx_total (int): The total number of transmissions to be made (when no script is passed)
+    - packet_length_seconds (float): The duration in seconds of a packet.
+
+    Methods:
+    - __init__(self, subclass=False): Initializes the TdmaScriptedMacNode instance.
+    - get_test_params(self): Retrieves the test parameters based on the current test index.
+    - set_rate_max_bytes_for_next_tx(self): Sets the rate and maximum bytes for the next transmission according to the test parameters.
+    - handle_packet_duration(self, packet_duration_seconds): Handles the packet duration based on the override_test_plan_packet_duration parameter.
+    - generate_tdma_scripted_status(self, basic_msg, scripted_msg): Generates a TDMA scripted status message.
+    - spin(self): Main loop for the TDMA scripted MAC node.
+    """
+    def __init__(self, subclass=False):
+        if not subclass:
+            rospy.init_node('tdma_scripted_mac')
+            self.tdma_status_publisher = rospy.Publisher('tdma_scripted_status', TdmaScriptedStatus, queue_size=0)
+        super().__init__(subclass=True)
+
+        # do scripted stuff
+        self.scripted_test_plan = rospy.get_param('~tdma_scripted_test_plan', None)
+        # use the packet_duration passed to this node rather than value in scripted_test_plan
+        self.override_test_plan_packet_duration = rospy.get_param('~override_test_plan_packet_duration', True)
+
+        self.tx_total = -1 # for case when no scripted plan is passed
+        if self.scripted_test_plan:
+            # we have a scripted test plan! set cycle counter starting index to 0
+            self.current_test_index = 0
+            self.tx_count = 0
+            self.tx_total = 1
+
+        if not subclass:
+            ## setup dynamic reconf for periodic ping params
+            # self.first_dynamic_reconf_scripted = True
+            # self.reconfigure_server = DynamicReconfigureServer(tdma_scriptedConfig, self.reconfigure_scripted)
+            # setup dynamic reconf for periodic ping params
+            self.first_dynamic_reconf = True
+            self.reconfigure_server = DynamicReconfigureServer(tdma_advancedConfig, self.reconfigure)
+
+            rospy.loginfo("tdma_scripted_mac node running.")
+            self.spin()
+
+    def get_test_params(self):
+        if self.scripted_test_plan:
+            if self.current_test_index >= len(self.scripted_test_plan['test_cycle']):
+                # back to the begining
+                self.current_test_index = 0
+                self.tx_count = 0
+
+            test_params = self.scripted_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.get(
+                        'maximum_miniframe_bytes', 
+                        PSK_ROS_FDP_Rates.FDP_MAX_BYTES_FOR_MINI_RATE[test_params['miniframe_rate']].default
+                    ), 
+                    default=None,
+                    packet_duration_ms=PSK_ROS_FDP_Rates.FDP_MAX_BYTES_FOR_MINI_RATE[test_params['miniframe_rate']].packet_duration_ms
+                )
+            fdp_data = FDPMaxBytes4Rate(
+                    rate=test_params['dataframe_rate'], 
+                    max_bytes=test_params.get(
+                        'maximum_dataframe_bytes', 
+                        PSK_ROS_FDP_Rates.FDP_MAX_BYTES_FOR_DATA_RATE[test_params['dataframe_rate']].default
+                    ), 
+                    default=None,
+                    packet_duration_ms=PSK_ROS_FDP_Rates.FDP_MAX_BYTES_FOR_DATA_RATE[test_params['dataframe_rate']].packet_duration_ms
+                )
+            script_packet_duration_sec = test_params.get('packet_duration_sec', (fdp_mini.packet_duration_ms + fdp_data.packet_duration_ms) // 1000)
+
+            if self.tx_total == 1:
+                tx_count_local = 1
+            else:
+                tx_count_local = self.tx_count
+
+            if self.tx_count >= self.tx_total or self.tx_total == 1:
+                rospy.logdebug(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:
+            tx_count_local = -1
+            fdp_mini = FDPMaxBytes4Rate(rate=self.miniframe_rate, max_bytes=self.maximum_miniframe_bytes, default=None, packet_duration_ms=PSK_ROS_FDP_Rates.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=PSK_ROS_FDP_Rates.FDP_MAX_BYTES_FOR_MINI_RATE[self.dataframe_rate].packet_duration_ms)
+            script_packet_duration_sec = (fdp_mini.packet_duration_ms + fdp_data.packet_duration_ms)
+
+        return fdp_mini, fdp_data, tx_count_local, script_packet_duration_sec
+
+    def set_rate_max_bytes_for_next_tx(self):
+        fdp_mini, fdp_data, tx_count_local, script_packet_duration_ms = self.get_test_params()
+
+        msg = TdmaScriptedStatus()
+        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.packet_duration_sec = self.packet_length_seconds
+
+        msg.this_cycle_tx_count = tx_count_local # num of times we have tx'd with the current settings (including this time)
+        msg.this_cycle_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
+
+        if tx_count_local != -1:
+            rospy.logdebug(f"TX {tx_count_local} /of/ {self.tx_total} times. Returning: {fdp_mini}, {fdp_data}, {tx_count_local}")
+            rospy.logdebug(f'Changed rate and max bytes for next TX:\n{msg}')
+
+        return script_packet_duration_ms, msg
+
+    def handle_packet_duration(self, packet_duration_seconds):
+        # if we aren't overriding the scripted_test_plans packet_duration with override_test_plan_packet_duration
+        # .. we need to get the packet length from the scripted_test_plan
+        if not self.override_test_plan_packet_duration:
+            self.packet_length_seconds = packet_duration_seconds
+
+    def generate_tdma_scripted_status(self, basic_msg, scripted_msg):
+        advanced_msg = self.generate_tdma_advanced_status(basic_msg=basic_msg)
+        scripted_msg.message = ''
+        scripted_msg.tdma_advanced_status = advanced_msg
+        return scripted_msg
+
+    def spin(self):
+        rate = rospy.Rate(5)
+        last_tx_time = 0
+        msg = None
+        scripted_msg = TdmaScriptedStatus()
+        sent_modem_pings = False
+        sent_transponder_ping = False
+        packet_duration_sec = None
+
+        while not rospy.is_shutdown():
+            if packet_duration_sec:
+                self.handle_packet_duration(packet_duration_seconds=packet_duration_sec)
+
+            msg = self.get_current_slot_info(software_mute=self.software_mute)
+            self.tdma_status_publisher.publish(self.generate_tdma_scripted_status(basic_msg=msg, scripted_msg=scripted_msg))
+
+            if self.can_transmit_now(msg=msg, last_tx_time=last_tx_time):
+                # we are active and have atleast enough time to send another packet
+                sent_modem_pings, sent_transponder_ping, update_last_tx = self.handle_queuing_packet(
+                        msg.current_slot, 
+                        msg.remaining_active_seconds, 
+                        sent_modem_pings, 
+                        sent_transponder_ping
+                    )
+                if update_last_tx:
+                    packet_duration_sec, scripted_msg = self.set_rate_max_bytes_for_next_tx()
+                    last_tx_time = rospy.get_time()
+                else:
+                    # nothing sent, sleep then check again
+                    rospy.logwarn_throttle(f'Nothing was sent even though we are active. We may have nothing to send or traffic that we have to send is not allowed in this slot.')
+                    rate.sleep()
+                    continue
+            else:
+                # not enough time. sleep for rate and try again
+                rate.sleep()
+                continue
+
+if __name__ == "__main__":
+    try:
+        tdma_state_node = TdmaScriptedMacNode()
+
+    except rospy.ROSInterruptException:
+        rospy.loginfo("tdma_node shutdown (interrupt)")
+
+
diff --git a/ros_acomms/src/tdma_test_mac_node.py b/ros_acomms/src/tdma_test_mac_node.py
deleted file mode 100755
index b9a69ec6c4c2891b480822c1a8c725bdab3b8a27..0000000000000000000000000000000000000000
--- a/ros_acomms/src/tdma_test_mac_node.py
+++ /dev/null
@@ -1,162 +0,0 @@
-#!/usr/bin/env python3
-
-import rospy
-from std_msgs.msg import Header
-from ros_acomms_msgs.msg import Packet, TdmaStatus, TdmaTestMacStatus
-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)
-        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
-        
-        rospy.loginfo("tdma_test_mac running")
-        self.spin()
-
-    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.get(
-                        'maximum_miniframe_bytes', 
-                        TdmaMacNode.FDP_MAX_BYTES_FOR_MINI_RATE[test_params['miniframe_rate']].default
-                    ), 
-                    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'], 
-                    max_bytes=test_params.get(
-                        'maximum_dataframe_bytes', 
-                        TdmaMacNode.FDP_MAX_BYTES_FOR_DATA_RATE[test_params['dataframe_rate']].default
-                    ), 
-                    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:
-                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, 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
-
-    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.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
-
-        # 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}')
-
-        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()
-                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
-
-            packet_duration_ms = 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)")
-
-
diff --git a/ros_acomms_examples/launch/modem_sim_tdma_nav_header.launch b/ros_acomms_examples/launch/modem_sim_tdma_nav_header.launch
deleted file mode 100644
index a093433c676f8bf13c4d7136306f5331b38a3944..0000000000000000000000000000000000000000
--- a/ros_acomms_examples/launch/modem_sim_tdma_nav_header.launch
+++ /dev/null
@@ -1,102 +0,0 @@
-<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="25000" 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="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>
-
-        <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.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.yaml" />
-        </node>
-        <node name="tdma_nav_header" pkg="ros_acomms" type="tdma_nav_header_node.py" output="screen" respawn="true" respawn_delay="10">
-            <rosparam>
-                active_slots: 0
-                num_slots: 2
-                slot_duration_seconds: 30
-                guard_time_seconds: 3
-                nav_duration_seconds: 15
-                nav_guard_time_seconds: 5
-                packet_length_seconds: 8
-                maximum_miniframe_bytes: 64
-                maximum_dataframe_bytes: 64
-                transponder_group_dest_id: 4
-                ping_modem_dest_id: 1
-                ping_modem_rate: 1
-                ping_modem_on: True
-                ping_transponders_on: False
-            </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="25000" 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="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>
-
-        <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.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.yaml" />
-        </node>
-        <node name="tdma_nav_header" pkg="ros_acomms" type="tdma_nav_header_node.py" output="screen" respawn="true" respawn_delay="10">
-            <rosparam>
-                active_slots: 1
-                num_slots: 2
-                slot_duration_seconds: 30
-                guard_time_seconds: 3
-                nav_duration_seconds: 15
-                nav_guard_time_seconds: 5
-                packet_length_seconds: 8
-                maximum_miniframe_bytes: 64
-                maximum_dataframe_bytes: 64
-                transponder_group_dest_id: 4
-                ping_modem_dest_id: 0
-                ping_modem_rate: 1
-                ping_modem_on: True
-                ping_transponders_on: False
-            </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/ros_acomms_examples/launch/modem_sim_tdma_test_mac.launch b/ros_acomms_examples/launch/modem_sim_tdma_test_mac.launch
deleted file mode 100644
index b1b90de6752b5c1525fce77f6637dfd8a493b7bf..0000000000000000000000000000000000000000
--- a/ros_acomms_examples/launch/modem_sim_tdma_test_mac.launch
+++ /dev/null
@@ -1,66 +0,0 @@
-<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: 1
-                slot_duration_seconds: 15
-                guard_time_seconds: 2
-                use_test_plan_packet_duration: True
-            </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="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/ros_acomms_examples/launch/modem_tdma_nav_header.launch b/ros_acomms_examples/launch/modem_tdma_nav_header.launch
deleted file mode 100644
index 976fa6493d99fe5ecfdaeff1c00fbb53b012f4a8..0000000000000000000000000000000000000000
--- a/ros_acomms_examples/launch/modem_tdma_nav_header.launch
+++ /dev/null
@@ -1,109 +0,0 @@
-<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_serial_port" value="/dev/ttyUSB2" type="str" />
-            <param name="modem_baud_rate" value="19200" type="int" />
-            <param name="pwramp_txlevel" value="3" type="int" />
-            <param name="set_modem_time" value="true" type="bool" />
-            <rosparam param="modem_config">
-                SRC: 0
-                BND: 0
-                FC0: 25000
-                BW0: 5000
-                SST: 1
-                pwramp.txlevel: 3
-                psk.packet.mod_hdr_version: 1
-            </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="tdma_nav_header" pkg="ros_acomms" type="tdma_nav_header_node.py" output="screen" respawn="true" respawn_delay="10">
-            <rosparam>
-                active_slots: 0
-                num_slots: 2
-                slot_duration_seconds: 30
-                guard_time_seconds: 3
-                nav_duration_seconds: 15
-                nav_guard_time_seconds: 5
-                packet_length_seconds: 8
-                maximum_miniframe_bytes: 64
-                maximum_dataframe_bytes: 64
-                transponder_A: True
-                transponder_B: True
-                transponder_C: True
-                transponder_D: True
-                transponder_reply_timeout_ms: 5000
-                ping_dest_id: 1
-                ping_rate: 1
-                cycle_rate_every_n_pings: 1
-                ping_cdr: "0x04"
-                ping_hex_data: ""
-                ping_modem_on: True
-                ping_transponders_on: False
-            </rosparam>
-        </node>
-
-    </group>
-
-    <group ns="modem1">
-        <node name="acomms_driver_node" pkg="ros_acomms" type="acomms_driver_node.py" output="screen" >
-            <param name="modem_serial_port" value="/dev/ttyUSB3" type="str" />
-            <param name="modem_baud_rate" value="19200" type="int" />
-            <param name="pwramp_txlevel" value="3" type="int" />
-            <param name="set_modem_time" value="true" type="bool" />
-            <rosparam param="modem_config">
-                SRC: 1
-                BND: 0
-                FC0: 25000
-                BW0: 5000
-                SST: 1
-                pwramp.txlevel: 3
-                psk.packet.mod_hdr_version: 1
-            </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="tdma_nav_header" pkg="ros_acomms" type="tdma_nav_header_node.py" output="screen" respawn="true" respawn_delay="10">
-            <rosparam>
-                active_slots: 1
-                num_slots: 2
-                slot_duration_seconds: 30
-                guard_time_seconds: 3
-                nav_duration_seconds: 15
-                nav_guard_time_seconds: 5
-                packet_length_seconds: 8
-                maximum_miniframe_bytes: 64
-                maximum_dataframe_bytes: 64
-                transponder_A: True
-                transponder_B: True
-                transponder_C: True
-                transponder_D: True
-                transponder_reply_timeout_ms: 5000
-                ping_dest_id: 0
-                ping_rate: 1
-                cycle_rate_every_n_pings: 1
-                ping_cdr: "0x04"
-                ping_hex_data: ""
-                ping_modem_on: True
-                ping_transponders_on: False
-            </rosparam>
-        </node>
-
-    </group>
-
-	<!-- <node name="test_modem_sim_node" pkg="ros_acomms" type="test_modem_sim_node.py" output="screen" /> -->
-
-
-</launch>
diff --git a/ros_acomms_examples/launch/tdma_test_plan.yaml b/ros_acomms_examples/launch/tdma_test_plan.yaml
deleted file mode 100644
index af4b0d256f8f3dba35e4b6199cec9a05c95ec466..0000000000000000000000000000000000000000
--- a/ros_acomms_examples/launch/tdma_test_plan.yaml
+++ /dev/null
@@ -1,21 +0,0 @@
-test_cycle:
-  - miniframe_rate: 1
-    dataframe_rate: 1
-
-  - 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/ros_acomms_examples/package.xml b/ros_acomms_examples/package.xml
index 0a66c144bd2622744ea08073f47ace5a3b42d29d..f9bfb470373bec832022d1bedddff677224c20ce 100644
--- a/ros_acomms_examples/package.xml
+++ b/ros_acomms_examples/package.xml
@@ -1,44 +1,30 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>ros_acomms_examples</name>
-  <version>6.1.0</version>
-  <description>ROS interface to Micromodem using pyacomms</description>
+  <version>9.0.0</version>
+  <description>ROS interface to Micromodem using pyacomms, Examples</description>
 
-  <!-- One maintainer tag required, multiple allowed, one person per tag --> 
-  <!-- Example:  -->
-  <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
+  <!-- START package wide section -->
+  <!-- MAINTAINERS, Copy changes made in this section of package.xml package wide -->
+  <!-- One maintainer tag required, multiple allowed, one person per tag -->
   <maintainer email="egallimore@whoi.edu">Eric Gallimore</maintainer>
   <maintainer email="cfitzgerald@whoi.edu">Caileigh Fitzgerald</maintainer>
 
   <!-- One license tag required, multiple allowed, one license per tag -->
-  <!-- Commonly used license strings: -->
-  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
   <license>LGPLv3</license>
 
   <!-- Url tags are optional, but multiple are allowed, one per tag -->
   <!-- Optional attribute type can be: website, bugtracker, or repository -->
-  <!-- Example: -->
-  <!-- <url type="website">http://wiki.ros.org/recon</url> -->
+  <url type="website">https://acomms.pages.whoi.edu/ros_acomms/</url>
 
   <!-- Author tags are optional, multiple are allowed, one per tag -->
   <!-- Authors do not have to be maintainers, but could be -->
   <author email="egallimore@whoi.edu">Eric Gallimore</author>
   <author email="cfitzgerald@whoi.edu">Caileigh Fitzgerald</author>
   <author email="dgiaya@whoi.edu">Dennis Giaya</author>
-
-
-  <!-- Url tags are optional, but multiple are allowed, one per tag -->
-  <!-- Optional attribute type can be: website, bugtracker, or repository -->
-  <!-- Example: -->
-  <!-- <url type="website">http://wiki.ros.org/ros_acomms_examples</url> -->
-
-
-  <!-- Author tags are optional, multiple are allowed, one per tag -->
-  <!-- Authors do not have to be maintainers, but could be -->
-  <!-- Example: -->
-  <!-- <author email="jane.doe@example.com">Jane Doe</author> -->
-
-
+  <!-- MAINTAINERS, Copy changes made in this section of package.xml package wide -->
+  <!-- END package wide section -->
+  
   <!-- The *depend tags are used to specify dependencies -->
   <!-- Dependencies can be catkin packages or system dependencies -->
   <!-- Examples: -->
diff --git a/ros_acomms_modeling/package.xml b/ros_acomms_modeling/package.xml
index bbce36e0a40ad0106e79198623d432edb9846282..8e6de6445791275d892246b971cffd50cc63163c 100644
--- a/ros_acomms_modeling/package.xml
+++ b/ros_acomms_modeling/package.xml
@@ -1,32 +1,30 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>ros_acomms_modeling</name>
-  <version>0.0.0</version>
-  <description>The ros_acomms_sim package</description>
+  <version>9.0.0</version>
+  <description>ROS interface to the Micromodem Simulator</description>
 
+  <!-- START package wide section -->
+  <!-- MAINTAINERS, Copy changes made in this section of package.xml package wide -->
   <!-- One maintainer tag required, multiple allowed, one person per tag -->
-  <!-- Example:  -->
-  <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
-  <maintainer email="brennan@todo.todo">brennan</maintainer>
-
+  <maintainer email="egallimore@whoi.edu">Eric Gallimore</maintainer>
+  <maintainer email="cfitzgerald@whoi.edu">Caileigh Fitzgerald</maintainer>
+  <maintainer email="millerklugmanb@wit.edu">Brennan Miller-Klugman </maintainer>
 
   <!-- One license tag required, multiple allowed, one license per tag -->
-  <!-- Commonly used license strings: -->
-  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
-  <license>TODO</license>
-
+  <license>LGPLv3</license>
 
   <!-- Url tags are optional, but multiple are allowed, one per tag -->
   <!-- Optional attribute type can be: website, bugtracker, or repository -->
-  <!-- Example: -->
-  <!-- <url type="website">http://wiki.ros.org/ros_acomms_sim</url> -->
-
+  <url type="website">https://acomms.pages.whoi.edu/ros_acomms/</url>
 
   <!-- Author tags are optional, multiple are allowed, one per tag -->
   <!-- Authors do not have to be maintainers, but could be -->
-  <!-- Example: -->
-  <!-- <author email="jane.doe@example.com">Jane Doe</author> -->
-
+  <author email="egallimore@whoi.edu">Eric Gallimore</author>
+  <author email="cfitzgerald@whoi.edu">Caileigh Fitzgerald</author>
+  <author email="dgiaya@whoi.edu">Dennis Giaya</author>
+  <!-- MAINTAINERS, Copy changes made in this section of package.xml package wide -->
+  <!-- END package wide section -->
 
   <!-- The *depend tags are used to specify dependencies -->
   <!-- Dependencies can be catkin packages or system dependencies -->
diff --git a/ros_acomms_msgs/CMakeLists.txt b/ros_acomms_msgs/CMakeLists.txt
index 7fa1704117375ea7b9cc8db4b7a46afb6ca8dd5e..b10270e3ac105e3429f51a571a2a3a92df2d5bea 100644
--- a/ros_acomms_msgs/CMakeLists.txt
+++ b/ros_acomms_msgs/CMakeLists.txt
@@ -66,8 +66,8 @@ add_message_files(FILES
   SummaryMessageCount.msg
   SoundSpeedProfile.msg
   TdmaStatus.msg
-  TdmaNavStatus.msg
-  TdmaTestMacStatus.msg
+  TdmaAdvancedStatus.msg
+  TdmaScriptedStatus.msg
   TransmittedPacket.msg
   UpdateQueuedMessage.msg
   XST.msg
diff --git a/ros_acomms_msgs/msg/TdmaAdvancedStatus.msg b/ros_acomms_msgs/msg/TdmaAdvancedStatus.msg
new file mode 100644
index 0000000000000000000000000000000000000000..4818c01be084eee4fe2080e58026d2b903fa1d01
--- /dev/null
+++ b/ros_acomms_msgs/msg/TdmaAdvancedStatus.msg
@@ -0,0 +1,17 @@
+bool software_mute
+string message
+
+int8 miniframe_rate
+int8 dataframe_rate
+int32 maximum_miniframe_bytes
+int32 maximum_dataframe_bytes
+int16 num_slots
+int8 active_slots
+int8 nav_slots
+int8 comms_slots
+
+int8 pings_per_slot
+int16 ping_modem_src
+bool ping_transponders
+
+TdmaStatus tdma_basic_status
diff --git a/ros_acomms_msgs/msg/TdmaNavStatus.msg b/ros_acomms_msgs/msg/TdmaNavStatus.msg
deleted file mode 100644
index a446f98510f96ec7f44ebd2eddd0e90127bfce44..0000000000000000000000000000000000000000
--- a/ros_acomms_msgs/msg/TdmaNavStatus.msg
+++ /dev/null
@@ -1,12 +0,0 @@
-#we_are_active, current_slot, remaining_slot_seconds, remaining_active_seconds, time_to_next_active
-
-Header header
-
-int8 current_slot
-bool we_are_active
-bool is_nav_portion
-float32 remaining_nav_seconds
-float32 remaining_slot_seconds
-float32 remaining_active_seconds
-float32 time_to_next_active
-string tdma_nav_mode
\ No newline at end of file
diff --git a/ros_acomms_msgs/msg/TdmaScriptedStatus.msg b/ros_acomms_msgs/msg/TdmaScriptedStatus.msg
new file mode 100644
index 0000000000000000000000000000000000000000..9d26d494382053c6806f403d4cb38d7862da6a1a
--- /dev/null
+++ b/ros_acomms_msgs/msg/TdmaScriptedStatus.msg
@@ -0,0 +1,13 @@
+string message
+
+int8 last_miniframe_rate
+int8 last_dataframe_rate
+int32 last_maximum_miniframe_bytes
+int32 last_maximum_dataframe_bytes
+
+int16 this_cycle_tx_count
+int16 this_cycle_tx_total
+
+float32 packet_duration_sec
+
+TdmaAdvancedStatus tdma_advanced_status
diff --git a/ros_acomms_msgs/msg/TdmaTestMacStatus.msg b/ros_acomms_msgs/msg/TdmaTestMacStatus.msg
deleted file mode 100644
index f5973e0dd0211ab3e5ec343b9d663901a14d1744..0000000000000000000000000000000000000000
--- a/ros_acomms_msgs/msg/TdmaTestMacStatus.msg
+++ /dev/null
@@ -1,16 +0,0 @@
-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
-
-int16 packet_length_seconds
diff --git a/ros_acomms_msgs/package.xml b/ros_acomms_msgs/package.xml
index 2b0b48f79e5c2c0d038ef1878043996ec21a7f12..fa3518d84fe9ab88d62751eec1d975b5649bad48 100644
--- a/ros_acomms_msgs/package.xml
+++ b/ros_acomms_msgs/package.xml
@@ -1,42 +1,29 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>ros_acomms_msgs</name>
-  <version>6.1.0</version>
+  <version>9.0.0</version>
   <description>ROS acomms messages</description>
 
-  <!-- One maintainer tag required, multiple allowed, one person per tag --> 
-  <!-- Example:  -->
-  <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
+  <!-- START package wide section -->
+  <!-- MAINTAINERS, Copy changes made in this section of package.xml package wide -->
+  <!-- One maintainer tag required, multiple allowed, one person per tag -->
   <maintainer email="egallimore@whoi.edu">Eric Gallimore</maintainer>
   <maintainer email="cfitzgerald@whoi.edu">Caileigh Fitzgerald</maintainer>
 
   <!-- One license tag required, multiple allowed, one license per tag -->
-  <!-- Commonly used license strings: -->
-  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
   <license>LGPLv3</license>
 
   <!-- Url tags are optional, but multiple are allowed, one per tag -->
   <!-- Optional attribute type can be: website, bugtracker, or repository -->
-  <!-- Example: -->
-  <!-- <url type="website">http://wiki.ros.org/recon</url> -->
+  <url type="website">https://acomms.pages.whoi.edu/ros_acomms/</url>
 
   <!-- Author tags are optional, multiple are allowed, one per tag -->
   <!-- Authors do not have to be maintainers, but could be -->
   <author email="egallimore@whoi.edu">Eric Gallimore</author>
   <author email="cfitzgerald@whoi.edu">Caileigh Fitzgerald</author>
   <author email="dgiaya@whoi.edu">Dennis Giaya</author>
-
-  <!-- Url tags are optional, but multiple are allowed, one per tag -->
-  <!-- Optional attribute type can be: website, bugtracker, or repository -->
-  <!-- Example: -->
-  <!-- <url type="website">http://wiki.ros.org/from ros_acomms_msgs.msg</url> -->
-
-
-  <!-- Author tags are optional, multiple are allowed, one per tag -->
-  <!-- Authors do not have to be maintainers, but could be -->
-  <!-- Example: -->
-  <!-- <author email="jane.doe@example.com">Jane Doe</author> -->
-
+  <!-- MAINTAINERS, Copy changes made in this section of package.xml package wide -->
+  <!-- END package wide section -->
 
   <!-- The *depend tags are used to specify dependencies -->
   <!-- Dependencies can be catkin packages or system dependencies -->
diff --git a/ros_acomms_tests/launch/tdma_hw_bench_test.launch b/ros_acomms_tests/launch/tdma_hw_bench_test.launch
new file mode 100644
index 0000000000000000000000000000000000000000..a6bef9984ac681ced39ca7bbeb0bd38168996ac7
--- /dev/null
+++ b/ros_acomms_tests/launch/tdma_hw_bench_test.launch
@@ -0,0 +1,94 @@
+<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_serial_port" value="/dev/ttyUSB1" type="str" />
+            <param name="modem_baud_rate" value="19200" type="int" />
+            <param name="pwramp_txlevel" value="3" type="int" />
+            <rosparam param="modem_config">
+                SRC: 0
+                BND: 0
+                FC0: 25000
+                BW0: 5000
+                pwramp.txlevel: 3
+                psk.packet.mod_hdr_version: 1
+            </rosparam>
+        </node>
+
+        <node name="tdma_scripted" pkg="ros_acomms" type="tdma_scripted_node.py" output="screen" required="true" respawn="false">
+            <rosparam param="tdma_scripted_test_plan" command="load" file="$(dirname)/tdma_scripted_test_plan.yaml" />
+            <rosparam>
+                active_slots: 0
+                num_slots: 2
+                slot_duration_seconds: 30
+                guard_time_seconds: 5
+                packet_length_seconds: 5
+                ping_modem: False
+                ping_modem_src: 1
+                pings_per_slot: 1
+                ping_cdr: 4
+                ping_transponders: False
+                override_test_plan_packet_duration: False
+            </rosparam>
+        </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_location_sim" pkg="ros_acomms_modeling" type="modem_location_sim_node.py" />
+    </group>
+
+    <group ns="modem1">
+        <node name="acomms_driver_node" pkg="ros_acomms" type="acomms_driver_node.py" output="screen" >
+            <param name="modem_serial_port" value="/dev/ttyUSB2" type="str" />
+            <param name="modem_baud_rate" value="19200" type="int" />
+            <param name="pwramp_txlevel" value="3" type="int" />
+            <rosparam param="modem_config">
+                SRC: 1
+                BND: 0
+                FC0: 25000
+                BW0: 5000
+                pwramp.txlevel: 3
+                psk.packet.mod_hdr_version: 1
+            </rosparam>
+        </node>
+
+        <node name="tdma_advanced" pkg="ros_acomms" type="tdma_advanced_node.py" output="screen" required="true" respawn="false">
+            <rosparam>
+                active_slots: 1
+                num_slots: 2
+                slot_duration_seconds: 30
+                guard_time_seconds: 5
+                packet_length_seconds: 5
+                ping_modem: False
+                ping_modem_src: 0
+                pings_per_slot: 1
+                ping_cdr: 8
+                ping_transponders: False
+            </rosparam>
+        </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_location_sim" pkg="ros_acomms_modeling" type="modem_location_sim_node.py" />
+    </group>
+
+    <node name="sim_packet_performance_node" pkg="ros_acomms_modeling" type="sim_packet_performance_node.py" />
+
+    <node name="sim_transmission_loss_node" pkg="ros_acomms_modeling" type="sim_transmission_loss_node.py"  >
+        <param name="water_depth" value="20" type="int" />
+        <param name="bellhop_arrivals" value="false" type="bool" />
+    </node>
+</launch>
diff --git a/ros_acomms_tests/launch/tdma_scripted_test_plan.yaml b/ros_acomms_tests/launch/tdma_scripted_test_plan.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..a15f8879c9bff623375212e0050427f9990e7b04
--- /dev/null
+++ b/ros_acomms_tests/launch/tdma_scripted_test_plan.yaml
@@ -0,0 +1,21 @@
+test_cycle:
+  - miniframe_rate: 1
+    dataframe_rate: 1
+    maximum_miniframe_bytes: 72
+    maximum_dataframe_bytes: 192
+    packet_tx_count: 2
+    packet_duration_sec: 3.0
+
+  - miniframe_rate: 3
+    dataframe_rate: 3
+    maximum_miniframe_bytes: 72
+    maximum_dataframe_bytes: 512
+    packet_tx_count: 2
+    packet_duration_sec: 3.5
+
+  - miniframe_rate: 5
+    dataframe_rate: 5
+    maximum_miniframe_bytes: 72
+    maximum_dataframe_bytes: 2048
+    packet_tx_count: 2
+    packet_duration_sec: 4.0
diff --git a/ros_acomms_tests/launch/test.launch b/ros_acomms_tests/launch/test.launch
index dfba6692c982e79c768077e7b3389391a16c1917..7c5f3f1456557986ec4095948c6ecccca79c4f4b 100644
--- a/ros_acomms_tests/launch/test.launch
+++ b/ros_acomms_tests/launch/test.launch
@@ -1,4 +1,6 @@
 <launch>
+    <arg name="tdma_type" default="tdma" doc="type of TDMA node to use: tdma, tdma_advanced, or tdma_scripted" />
+
     <env name="ROSCONSOLE_FORMAT" value="[${severity}] [${time}] [${node}]: ${message}"/>
 
     <param name="use_sim_time" value="true"/>
@@ -10,8 +12,8 @@
             <param name="SRC" value="0" type="int" />
         </node>
 
-        <node name="tdma" pkg="ros_acomms" type="tdma_node.py" output="screen" required="true" respawn="false">
-            <param name="num_slots" value="2"/>
+        <node name="tdma" pkg="ros_acomms" type="$(arg tdma_type)_node.py" output="screen" required="true" respawn="false">
+            <param name="num_slots" value="3"/>
             <param name="active_slots" value="0"/>
             <param name="slot_duration_seconds" value="30" />
         </node>
@@ -35,8 +37,8 @@
             <param name="SRC" value="1" type="int" />
         </node>
 
-        <node name="tdma" pkg="ros_acomms" type="tdma_node.py" output="screen" required="true" respawn="false">
-            <param name="num_slots" value="2"/>
+        <node name="tdma_advanced" pkg="ros_acomms" type="$(arg tdma_type)_node.py" output="screen" required="true" respawn="false">
+            <param name="num_slots" value="3"/>
             <param name="active_slots" value="1"/>
             <param name="slot_duration_seconds" value="30" />
         </node>
diff --git a/ros_acomms_tests/package.xml b/ros_acomms_tests/package.xml
index 5ce58f15a875d3ee7b7b62bcdef453bec0bd8d5c..a902ba6eb10b8cb5fc93e1e8ab93d5e52dd1ce7b 100644
--- a/ros_acomms_tests/package.xml
+++ b/ros_acomms_tests/package.xml
@@ -1,43 +1,29 @@
 <?xml version="1.0"?>
 <package format="2">
   <name>ros_acomms_tests</name>
-  <version>6.1.0</version>
+  <version>9.0.0</version>
   <description>ROS acomms test package</description>
 
-  <!-- One maintainer tag required, multiple allowed, one person per tag --> 
-  <!-- Example:  -->
-  <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
+  <!-- START package wide section -->
+  <!-- MAINTAINERS, Copy changes made in this section of package.xml package wide -->
+  <!-- One maintainer tag required, multiple allowed, one person per tag -->
   <maintainer email="egallimore@whoi.edu">Eric Gallimore</maintainer>
   <maintainer email="cfitzgerald@whoi.edu">Caileigh Fitzgerald</maintainer>
 
   <!-- One license tag required, multiple allowed, one license per tag -->
-  <!-- Commonly used license strings: -->
-  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
   <license>LGPLv3</license>
 
   <!-- Url tags are optional, but multiple are allowed, one per tag -->
   <!-- Optional attribute type can be: website, bugtracker, or repository -->
-  <!-- Example: -->
-  <!-- <url type="website">http://wiki.ros.org/recon</url> -->
+  <url type="website">https://acomms.pages.whoi.edu/ros_acomms/</url>
 
   <!-- Author tags are optional, multiple are allowed, one per tag -->
   <!-- Authors do not have to be maintainers, but could be -->
   <author email="egallimore@whoi.edu">Eric Gallimore</author>
   <author email="cfitzgerald@whoi.edu">Caileigh Fitzgerald</author>
   <author email="dgiaya@whoi.edu">Dennis Giaya</author>
-
-
-  <!-- Url tags are optional, but multiple are allowed, one per tag -->
-  <!-- Optional attribute type can be: website, bugtracker, or repository -->
-  <!-- Example: -->
-  <!-- <url type="website">http://wiki.ros.org/ros_acomms_test</url> -->
-
-
-  <!-- Author tags are optional, multiple are allowed, one per tag -->
-  <!-- Authors do not have to be maintainers, but could be -->
-  <!-- Example: -->
-  <!-- <author email="jane.doe@example.com">Jane Doe</author> -->
-
+  <!-- MAINTAINERS, Copy changes made in this section of package.xml package wide -->
+  <!-- END package wide section -->
 
   <!-- The *depend tags are used to specify dependencies -->
   <!-- Dependencies can be catkin packages or system dependencies -->
diff --git a/ros_acomms_tests/src/test_dynamic_queue.py b/ros_acomms_tests/src/test_dynamic_queue.py
index 718f8d91ddbd8455a6c63dc2bd8cf29700a20e68..444ab5f8325ce18aa0514f6e4830b685a50df498 100755
--- a/ros_acomms_tests/src/test_dynamic_queue.py
+++ b/ros_acomms_tests/src/test_dynamic_queue.py
@@ -62,6 +62,8 @@ class TestDynamicQueue:
 
         rospy.init_node("test_dynamic_queue", log_level=rospy.INFO)
 
+        tdma_type = rospy.get_param("~tdma_type", "tdma")
+
         self.rospack = rospkg.RosPack()
 
         uuid = roslaunch.rlutil.get_or_generate_uuid(None, False)
@@ -72,7 +74,12 @@ class TestDynamicQueue:
             "launch/dynamic_queue_test.launch",
         )
         self.helper = Helper()
-        self.launch = roslaunch.parent.ROSLaunchParent(uuid, [launch_file])
+
+        roslaunch_args = [f"tdma_type:={tdma_type}"]
+        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() 
     
 
diff --git a/ros_acomms_tests/src/test_ros_acomms.py b/ros_acomms_tests/src/test_ros_acomms.py
index b5d4b394baac00e65c7cdb8d2b9363838d35b87d..9f54250b3b29b49752ad6e30acef69fc71ec38d5 100755
--- a/ros_acomms_tests/src/test_ros_acomms.py
+++ b/ros_acomms_tests/src/test_ros_acomms.py
@@ -27,6 +27,8 @@ class TestRosAcomms:
         self.test_counter = 0
         rospy.init_node("ros_acomms_tests", log_level=rospy.INFO)
 
+        tdma_type = rospy.get_param("~tdma_type", "tdma")
+
         self.rospack = rospkg.RosPack()
 
         uuid = roslaunch.rlutil.get_or_generate_uuid(None, False)
@@ -37,7 +39,11 @@ class TestRosAcomms:
             "launch/test.launch",
         )
 
-        self.launch = roslaunch.parent.ROSLaunchParent(uuid, [launch_file])
+        roslaunch_args = [f"tdma_type:={tdma_type}"]
+        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)