From 01f6266e431200cb06d60731bc0f3615586f9b69 Mon Sep 17 00:00:00 2001 From: Eric Gallimore <egallimore@whoi.edu> Date: Mon, 3 Jul 2023 11:19:32 -0700 Subject: [PATCH 1/6] Added a node to publish /clock so that we can try simulating faster than real-time. --- ros_acomms_tests/launch/test.launch | 6 +----- ros_acomms_tests/src/clock_generator.py | 25 +++++++++++++++++++++++++ 2 files changed, 26 insertions(+), 5 deletions(-) create mode 100755 ros_acomms_tests/src/clock_generator.py diff --git a/ros_acomms_tests/launch/test.launch b/ros_acomms_tests/launch/test.launch index 9d5761e9..b9b9cbb3 100644 --- a/ros_acomms_tests/launch/test.launch +++ b/ros_acomms_tests/launch/test.launch @@ -61,10 +61,6 @@ <!--<node name="test_modem_sim_node" pkg="ros_acomms" type="test_modem_sim_node.py" output="screen" />--> - - - - - + <node name="clock_generator" pkg="ros_acomms_tests" type="clock_generator.py" /> </launch> diff --git a/ros_acomms_tests/src/clock_generator.py b/ros_acomms_tests/src/clock_generator.py new file mode 100755 index 00000000..4ff33a23 --- /dev/null +++ b/ros_acomms_tests/src/clock_generator.py @@ -0,0 +1,25 @@ +import rospy +from rosgraph_msgs.msg import Clock +from threading import sleep + + +def clock_generator(): + clock_publisher = rospy.Publisher('clock', Clock, queue_size=10) + rospy.init_node('clock_generator', anonymous=True) + rate = rospy.Rate(rospy.get_param("~publish_rate", 50)) + sim_speed_multiplier = rospy.get_param("~multiplier", 5) + sim_clock_msg = Clock() + current_time = rospy.get_time() + + while not rospy.is_shutdown(): + current_time += (1 / rate) * sim_speed_multiplier + sim_clock_msg.clock = rospy.Time.from_sec(current_time) + clock_publisher.publish(sim_clock_msg) + sleep(1 / rate) + + +if __name__ == '__main__': + try: + clock_generator() + except rospy.ROSInterruptException: + pass \ No newline at end of file -- GitLab From 97c617ce2e2d9e3759b502619d4491c2ad0799af Mon Sep 17 00:00:00 2001 From: Eric Gallimore <egallimore@whoi.edu> Date: Mon, 3 Jul 2023 11:22:27 -0700 Subject: [PATCH 2/6] Add use_sim_time param so we actually use sim time. --- ros_acomms_tests/launch/test.launch | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ros_acomms_tests/launch/test.launch b/ros_acomms_tests/launch/test.launch index b9b9cbb3..fec651b7 100644 --- a/ros_acomms_tests/launch/test.launch +++ b/ros_acomms_tests/launch/test.launch @@ -1,6 +1,8 @@ <launch> <env name="ROSCONSOLE_FORMAT" value="[${severity}] [${time}] [${node}]: ${message}"/> + <param name="use_sim_time" value="true"> + <group ns="modem0"> <node name="modem_sim_node" pkg="ros_acomms_modeling" type="modem_sim_node.py" output="screen" > <param name="center_frequency_hz" value="10000" type="int" /> -- GitLab From c1083d93fe9df0d5249bb6513fb4ffc70c3997f1 Mon Sep 17 00:00:00 2001 From: Eric Gallimore <egallimore@whoi.edu> Date: Mon, 3 Jul 2023 11:23:37 -0700 Subject: [PATCH 3/6] Added missing shebang. --- ros_acomms_tests/src/clock_generator.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ros_acomms_tests/src/clock_generator.py b/ros_acomms_tests/src/clock_generator.py index 4ff33a23..2d076080 100755 --- a/ros_acomms_tests/src/clock_generator.py +++ b/ros_acomms_tests/src/clock_generator.py @@ -1,3 +1,5 @@ +#! /usr/bin/env python3 + import rospy from rosgraph_msgs.msg import Clock from threading import sleep -- GitLab From f2c87a1f746deac5ee4fc1b6cc1d8ebd56e9e19c Mon Sep 17 00:00:00 2001 From: Eric Gallimore <egallimore@whoi.edu> Date: Mon, 3 Jul 2023 11:26:41 -0700 Subject: [PATCH 4/6] Fixed xml --- ros_acomms_tests/launch/test.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_acomms_tests/launch/test.launch b/ros_acomms_tests/launch/test.launch index fec651b7..2a54438e 100644 --- a/ros_acomms_tests/launch/test.launch +++ b/ros_acomms_tests/launch/test.launch @@ -1,7 +1,7 @@ <launch> <env name="ROSCONSOLE_FORMAT" value="[${severity}] [${time}] [${node}]: ${message}"/> - <param name="use_sim_time" value="true"> + <param name="use_sim_time" value="true"/> <group ns="modem0"> <node name="modem_sim_node" pkg="ros_acomms_modeling" type="modem_sim_node.py" output="screen" > -- GitLab From 50b630d6e505266c2ed7379c2f4aa26897e06049 Mon Sep 17 00:00:00 2001 From: Eric Gallimore <egallimore@whoi.edu> Date: Mon, 3 Jul 2023 11:31:19 -0700 Subject: [PATCH 5/6] Use a sleep function that exists. --- ros_acomms_tests/src/clock_generator.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_acomms_tests/src/clock_generator.py b/ros_acomms_tests/src/clock_generator.py index 2d076080..f6d58938 100755 --- a/ros_acomms_tests/src/clock_generator.py +++ b/ros_acomms_tests/src/clock_generator.py @@ -2,7 +2,7 @@ import rospy from rosgraph_msgs.msg import Clock -from threading import sleep +from time import sleep def clock_generator(): -- GitLab From 3f6c6e60f8789886eddffc38fcfce2b2f4eb3e63 Mon Sep 17 00:00:00 2001 From: Eric Gallimore <egallimore@whoi.edu> Date: Mon, 3 Jul 2023 11:35:25 -0700 Subject: [PATCH 6/6] Don't cast a float as a Rate --- ros_acomms_tests/src/clock_generator.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ros_acomms_tests/src/clock_generator.py b/ros_acomms_tests/src/clock_generator.py index f6d58938..49cadc18 100755 --- a/ros_acomms_tests/src/clock_generator.py +++ b/ros_acomms_tests/src/clock_generator.py @@ -8,7 +8,7 @@ from time import sleep def clock_generator(): clock_publisher = rospy.Publisher('clock', Clock, queue_size=10) rospy.init_node('clock_generator', anonymous=True) - rate = rospy.Rate(rospy.get_param("~publish_rate", 50)) + rate = rospy.get_param("~publish_rate", 50) sim_speed_multiplier = rospy.get_param("~multiplier", 5) sim_clock_msg = Clock() current_time = rospy.get_time() -- GitLab