From 858196f001f1864c4bbce49f8381f835122490e2 Mon Sep 17 00:00:00 2001 From: TiaSinghania Date: Tue, 22 Oct 2024 21:11:31 -0400 Subject: [PATCH] implemented callback in loop with timer --- rb_ws/src/buggy/buggy/simulator/engine.py | 49 +++++++++++++++++++++ rb_ws/src/buggy/launch/sim_2d_single.xml | 10 ++--- rb_ws/src/buggy/scripts/simulator/engine.py | 32 -------------- rb_ws/src/buggy/setup.py | 7 ++- 4 files changed, 57 insertions(+), 41 deletions(-) create mode 100644 rb_ws/src/buggy/buggy/simulator/engine.py delete mode 100644 rb_ws/src/buggy/scripts/simulator/engine.py diff --git a/rb_ws/src/buggy/buggy/simulator/engine.py b/rb_ws/src/buggy/buggy/simulator/engine.py new file mode 100644 index 00000000..346ae3aa --- /dev/null +++ b/rb_ws/src/buggy/buggy/simulator/engine.py @@ -0,0 +1,49 @@ +#! /usr/bin/env python3 +import sys +import time +import rclpy +from rclpy.node import Node + +from std_msgs.msg import String, Float64 + +class Simulator(Node): + # simulator constants: + + def __init__(self): + super().__init__('SC_sim_single') + self.get_logger().info("INITIALIZING") + self.number_publisher = self.create_publisher(Float64, 'numbers', 1) + self.test_publisher = self.create_publisher(String, 'test', 1) + self.i = 0 + + self.buggy_name = "NONE" + + if (self.get_namespace() == "/SC"): + self.buggy_name = "SC" + + if (self.get_namespace() == "/NAND"): + self.buggy_name = "NAND" + + freq = 10 + timer_period = 1/freq # seconds + self.timer = self.create_timer(timer_period, self.loop) + + def loop(self): + + self.get_logger().info("LOOPING") + + msg = String() + msg.data = self.buggy_name + self.test_publisher.publish(msg) + msg2 = Float64() + msg2.data = float(self.i) + self.number_publisher.publish(msg2) + self.i += 1 + +def main(args=None): + rclpy.init(args=args) + sim = Simulator() + sim.get_logger().info("CREATED NODE") + rclpy.spin(sim) + + diff --git a/rb_ws/src/buggy/launch/sim_2d_single.xml b/rb_ws/src/buggy/launch/sim_2d_single.xml index 0aed958d..550c2591 100755 --- a/rb_ws/src/buggy/launch/sim_2d_single.xml +++ b/rb_ws/src/buggy/launch/sim_2d_single.xml @@ -1,9 +1,9 @@ - - - + + + - - + \ No newline at end of file diff --git a/rb_ws/src/buggy/scripts/simulator/engine.py b/rb_ws/src/buggy/scripts/simulator/engine.py deleted file mode 100644 index d0bab707..00000000 --- a/rb_ws/src/buggy/scripts/simulator/engine.py +++ /dev/null @@ -1,32 +0,0 @@ -#! /usr/bin/env python3 -import sys -import time -import rclpy -from std_msgs.msg import String - -class Simulator(): - # simulator constants: - - def __init__(self): - self.test_publisher = self.create_publisher(String, 'test', 10) - if (self.get_namespace() == "SC"): - self.buggy_name = "SC" - - if (self.get_namespace() == "NAND"): - self.buggy_name = "NAND" - - def loop(self): - print("hello") - self.test_publisher.publish(self.buggy_name) - -if __name__ == "__main__": - rclpy.init() - sim = Simulator() - - # publish initial position, then sleep - # so that auton stack has time to initialize - # before buggy moves - time.sleep(15.0) - sim.loop() - - diff --git a/rb_ws/src/buggy/setup.py b/rb_ws/src/buggy/setup.py index b8edf928..42b86b1a 100644 --- a/rb_ws/src/buggy/setup.py +++ b/rb_ws/src/buggy/setup.py @@ -13,7 +13,7 @@ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), - (os.path.join("share", package_name), glob("launch/*.xml")), + (os.path.join("share", package_name), glob("launch/*.xml")) ], install_requires=['setuptools'], zip_safe=True, @@ -24,9 +24,8 @@ tests_require=['pytest'], entry_points={ 'console_scripts': [ - 'hello_world = buggy.hello_world:main' - 'sim-single = buggy.engine:main' - + 'hello_world = buggy.hello_world:main', + 'sim_single = buggy.simulator.engine:main' ], }, )