diff --git a/rb_ws/src/buggy/launch/sim_2d_double.xml b/rb_ws/src/buggy/launch/sim_2d_double.xml index 17eb93d..b9d5ba6 100644 --- a/rb_ws/src/buggy/launch/sim_2d_double.xml +++ b/rb_ws/src/buggy/launch/sim_2d_double.xml @@ -1,29 +1,29 @@ - + - - + + - + - - + + - + - + diff --git a/rb_ws/src/buggy/scripts/simulator/engine.py b/rb_ws/src/buggy/scripts/simulator/engine.py index 26d82c6..f0fe89a 100755 --- a/rb_ws/src/buggy/scripts/simulator/engine.py +++ b/rb_ws/src/buggy/scripts/simulator/engine.py @@ -9,6 +9,8 @@ from nav_msgs.msg import Odometry import numpy as np import utm +import time + sys.path.append("/rb_ws/src/buggy/scripts") from util.constants import Constants @@ -130,7 +132,7 @@ def publish(self): with self.lock: p.position.x = self.e_utm p.position.y = self.n_utm - p.position.z = self.heading + p.position.z = float(self.heading) velocity = self.velocity self.plot_publisher.publish(p) @@ -182,6 +184,12 @@ def loop(self): def main(args=None): rclpy.init(args=args) sim = Simulator() + for i in range(500): + time.sleep(0.01) + sim.publish() + + + sim.get_logger().info("STARTED PUBLISHING") rclpy.spin(sim) sim.destroy_node()