From efdaf314c2cf8408dcc537fbde3363de0dd6c35a Mon Sep 17 00:00:00 2001
From: Eric Gallimore <egallimore@whoi.edu>
Date: Wed, 7 Apr 2021 20:28:35 +0000
Subject: [PATCH] Fixed modem sim so that it runs without groundtruth and
 tick/tock synchronization.  Changed a bunch of verbose log messages from info
 to debug.

(cherry picked from commit 9ec469be93a5d3536028de73514aec8aef5df4fb)
---
 launch/modem_sim_test.launch  | 18 ++++++++++--------
 src/modem_sim_node.py         | 27 ++++++++++++++++++---------
 src/platform_location_node.py |  2 +-
 src/test_modem_sim_node.py    |  5 ++---
 4 files changed, 31 insertions(+), 21 deletions(-)

diff --git a/launch/modem_sim_test.launch b/launch/modem_sim_test.launch
index a4536e57..06da2738 100644
--- a/launch/modem_sim_test.launch
+++ b/launch/modem_sim_test.launch
@@ -3,17 +3,19 @@
 
     <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="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>
     </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="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>
     </group>
 
@@ -22,8 +24,8 @@
 	<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" />
+	    <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" />
diff --git a/src/modem_sim_node.py b/src/modem_sim_node.py
index 2655d634..92801b61 100755
--- a/src/modem_sim_node.py
+++ b/src/modem_sim_node.py
@@ -55,8 +55,12 @@ class ModemSimNode(object):
         self.ambient_noise = rospy.get_param('~ambient_noise_db', default=60)
 
         use_sim_tick_name = rospy.search_param('use_sim_tick')
-        self.use_sim_tick = rospy.get_param(use_sim_tick_name, default=False)
+        if use_sim_tick_name:
+            self.use_sim_tick = rospy.get_param(use_sim_tick_name, default=False)
+        else:
+            self.use_sim_tick = False
         rospy.loginfo("use_sim_tick {} ".format(self.use_sim_tick))
+
         tick_topic_name_param = rospy.search_param('tick_topic_name')
         rospy.loginfo("tick_topic_name {} ".format(tick_topic_name_param))
         if tick_topic_name_param:
@@ -148,20 +152,20 @@ class ModemSimNode(object):
                 else:
                     current_time = rospy.Time.now()
 
-                rospy.loginfo("Processing timestep.")
+                rospy.logdebug("Processing timestep.")
 
                 # Now, check to see if we have items in the queue.  We want to consume everything that is ready, but
                 # not block.
                 while True:
                     try:
-                        rospy.loginfo("Trying to add to inwater queue")
+                        rospy.logdebug("Trying to add to inwater queue")
                         new_packet = self.incoming_packets_queue.get_nowait()
                         self.packets_in_the_water.append(new_packet)
                         rospy.loginfo("MODEM %d: Added new packet to inwater queue", self.src)
                     except Empty:
                         break
 
-                rospy.loginfo("Processing inwater packets.")
+                rospy.logdebug("Processing inwater packets.")
 
                 # Now, run the receive loop for this time tick
                 self.process_inwater_packets(current_time=current_time)
@@ -175,7 +179,7 @@ class ModemSimNode(object):
                     header = Header(stamp=stamp)
                     tock = Tock(header=header, node_name=self.node_name, status=0, step_id=tick.step_id)
                     self.sim_tock_publisher.publish(tock)
-                    rospy.loginfo("Published Tock {} for {}.".format(tick.step_id, self.node_name))
+                    rospy.logdebug("Published Tock {} for {}.".format(tick.step_id, self.node_name))
                 else:
                     # If we aren't using sim ticks, just sleep this thread for a bit
                     rospy.sleep(0.1)
@@ -226,7 +230,7 @@ class ModemSimNode(object):
     def process_inwater_packets(self, current_time) -> None:
         rcv_platform_location = self.get_ownship_location()
 
-        rospy.loginfo("MODEM {}: location is {}".format(self.src, rcv_platform_location))
+        rospy.logdebug("MODEM {}: location is {}".format(self.src, rcv_platform_location))
 
         # Look at all the packets in the water and see if any of them are being received right now.
         for packet_in_the_water in self.packets_in_the_water:
@@ -234,6 +238,7 @@ class ModemSimNode(object):
             if active_packet:
                 self.packets_in_the_water.remove(packet_in_the_water)
                 self.active_rx_packets.append(active_packet)
+                rospy.loginfo_throttle(1, "MODEM {}: Incoming packet receive start".format(self.src))
 
         # If there are no active packets, we are done with this cycle.
         if not self.active_rx_packets:
@@ -269,7 +274,7 @@ class ModemSimNode(object):
             packet_performance_req = SimPacketPerformanceRequest()
             packet_performance_req.rx_level_db = finished_packet.receive_level_db
             packet_performance_req.noise_level_db = total_noise
-            packet_performance_req.packet_rate = finished_packet.sim_packet.packet.packet_rate
+            packet_performance_req.packet_rate = finished_packet.sim_packet.packet.dataframe_rate
             packet_performance = self.call_sim_packet_performance(packet_performance_req)
 
             if packet_performance.packet_success is True:
@@ -347,6 +352,10 @@ class ModemSimNode(object):
     def call_get_platform_location(self):
         try:
             rospy.logdebug("Trying to get platform location")
+            if self.modem_location_source == 'local_service':
+                from ros_acomms.srv import GetPlatformLocation as ReadLocation
+                from ros_acomms.srv import GetPlatformLocationRequest as ReadLocationRequest
+                from ros_acomms.srv import GetPlatformLocationResponse as ReadLocationResponse
             get_platform_location = rospy.ServiceProxy('/read_location', ReadLocation)
             platform_location_req = ReadLocationRequest()
             platform_location_req.name = rospy.get_namespace()
@@ -357,10 +366,10 @@ class ModemSimNode(object):
                                                                                            platform_location.latitude,
                                                                                            platform_location.longitude,
                                                                                            platform_location.depth)
-            rospy.loginfo(log_str)
+            rospy.logdebug(log_str)
             return platform_location
         except rospy.ServiceException:
-            rospy.loginfo("MODEM %d: Get Platform Location Service call failed", self.src)
+            rospy.logwarn_throttle(1, "MODEM %d: Get Platform Location Service call failed", self.src)
 
     """ Calls SimPacketPerformance Service """
 
diff --git a/src/platform_location_node.py b/src/platform_location_node.py
index 267b001f..43b9aecc 100755
--- a/src/platform_location_node.py
+++ b/src/platform_location_node.py
@@ -13,7 +13,7 @@ class PlatformLocationNode(object):
         platform_location.spin()
 
     def handle_get_platform_location(self, req):
-        rospy.loginfo("Getting Platform Location for SRC %s", req.name)
+        rospy.logdebug("Getting Platform Location for SRC %s", req.name)
         # Using same setup as test_sim_transmission_loss - don't care about the source
         lat = random.randrange(41421580, 41553703) * (10 ** -6)
         lon = random.randrange(70726027, 70843443) * -(10 ** -6)
diff --git a/src/test_modem_sim_node.py b/src/test_modem_sim_node.py
index c29210de..743a7174 100755
--- a/src/test_modem_sim_node.py
+++ b/src/test_modem_sim_node.py
@@ -10,9 +10,8 @@ def test_queue_tx_packet_call(packet_counter):
 
     try:
         rospy.loginfo("Queuing Packet for TX")
-        queue_packet = Packet()
-        queue_packet.packet_rate = 1
-        queue_packet.dest = packet_counter
+        packet_counter = packet_counter % 255
+        queue_packet = Packet(dest=packet_counter, miniframe_rate=1, dataframe_rate=1)
 
         queue_tx = rospy.ServiceProxy('/modem0/queue_tx_packet', QueueTxPacket)
         req = QueueTxPacketRequest(queue=1,
-- 
GitLab