diff --git a/.gitignore b/.gitignore
index 88667fb..21e2554 100644
--- a/.gitignore
+++ b/.gitignore
@@ -6,7 +6,7 @@ docker-compose.yml~
# BAGS
rb_ws/bags
-rb_ws/src/buggy/bags/*
+rb_ws/src/buggy/bags/
*.bag
rb_ws/rosbag2/
diff --git a/rb_ws/src/buggy/config/sim_double.yaml b/rb_ws/src/buggy/config/sim_double.yaml
new file mode 100644
index 0000000..af2e085
--- /dev/null
+++ b/rb_ws/src/buggy/config/sim_double.yaml
@@ -0,0 +1,34 @@
+/**: # Global Params
+ ros__parameters:
+ traj_name: "buggycourse_safe.json"
+
+NAND:
+ NAND_sim_single:
+ ros__parameters:
+ velocity: 10
+ pose: "Hill1_NAND"
+
+ NAND_controller:
+ ros__parameters:
+ dist: 0.0
+ # traj_name: "buggycourse_safe.json"
+ controller: "stanley"
+
+SC:
+ SC_sim_single:
+ ros__parameters:
+ velocity: 12
+ pose: "Hill1_SC"
+
+SC:
+ SC_controller:
+ ros__parameters:
+ dist: 0.0
+ # traj_name: "buggycourse_safe.json"
+ controller: "stanley"
+
+SC:
+ SC_path_planner:
+ ros__parameters:
+ traj_name: "buggycourse_safe.json"
+ curb_name: "buggycourse_curb.json"
diff --git a/rb_ws/src/buggy/config/sim_single_sc.yaml b/rb_ws/src/buggy/config/sim_single_sc.yaml
new file mode 100644
index 0000000..5d9b8cf
--- /dev/null
+++ b/rb_ws/src/buggy/config/sim_single_sc.yaml
@@ -0,0 +1,10 @@
+SC:
+ SC_sim_single:
+ ros__parameters:
+ velocity: 12
+ pose: "Hill1_SC"
+ SC_controller:
+ ros__parameters:
+ dist: 0.0
+ traj_name: "buggycourse_safe.json"
+ controller: "stanley"
diff --git a/rb_ws/src/buggy/launch/sim_2d_double.xml b/rb_ws/src/buggy/launch/sim_2d_double.xml
index b9d5ba6..545f5aa 100644
--- a/rb_ws/src/buggy/launch/sim_2d_double.xml
+++ b/rb_ws/src/buggy/launch/sim_2d_double.xml
@@ -1,31 +1,26 @@
+
+
-
-
-
+
-
-
+
-
-
-
+
-
-
+
-
-
+
\ No newline at end of file
diff --git a/rb_ws/src/buggy/launch/sim_2d_single.xml b/rb_ws/src/buggy/launch/sim_2d_single.xml
index f0e7204..508dc4c 100755
--- a/rb_ws/src/buggy/launch/sim_2d_single.xml
+++ b/rb_ws/src/buggy/launch/sim_2d_single.xml
@@ -1,15 +1,14 @@
+
+
-
-
+
-
-
-
+
\ No newline at end of file
diff --git a/rb_ws/src/buggy/scripts/buggy_state_converter.py b/rb_ws/src/buggy/scripts/buggy_state_converter.py
index acc3d80..a864c28 100755
--- a/rb_ws/src/buggy/scripts/buggy_state_converter.py
+++ b/rb_ws/src/buggy/scripts/buggy_state_converter.py
@@ -10,6 +10,7 @@
class BuggyStateConverter(Node):
def __init__(self):
super().__init__("buggy_state_converter")
+ self.get_logger().info('INITIALIZED.')
namespace = self.get_namespace()
if namespace == "/SC":
diff --git a/rb_ws/src/buggy/scripts/controller/controller_node.py b/rb_ws/src/buggy/scripts/controller/controller_node.py
index 3094ca8..1461a33 100755
--- a/rb_ws/src/buggy/scripts/controller/controller_node.py
+++ b/rb_ws/src/buggy/scripts/controller/controller_node.py
@@ -40,9 +40,9 @@ def __init__(self):
start_index = self.cur_traj.get_index_from_distance(start_dist)
- self.declare_parameter("controller_name", "stanley")
+ self.declare_parameter("controller", "stanley")
- controller_name = self.get_parameter("controller_name").value
+ controller_name = self.get_parameter("controller").value
print(controller_name.lower)
if (controller_name.lower() == "stanley"):
self.controller = StanleyController(start_index = start_index, namespace = self.get_namespace(), node=self) #IMPORT STANLEY
diff --git a/rb_ws/src/buggy/scripts/controller/stanley_controller.py b/rb_ws/src/buggy/scripts/controller/stanley_controller.py
index ce9b811..8c3ac1c 100755
--- a/rb_ws/src/buggy/scripts/controller/stanley_controller.py
+++ b/rb_ws/src/buggy/scripts/controller/stanley_controller.py
@@ -48,7 +48,7 @@ def compute_control(self, state_msg : Odometry, trajectory : Trajectory):
float (desired steering angle)
"""
if self.current_traj_index >= trajectory.get_num_points() - 1:
- self.node.get_logger.error("[Stanley]: Ran out of path to follow!")
+ self.node.get_logger().error("[Stanley]: Ran out of path to follow!")
raise Exception("[Stanley]: Ran out of path to follow!")
current_rospose = state_msg.pose.pose
diff --git a/rb_ws/src/buggy/scripts/serial/ros_to_bnyahaj.py b/rb_ws/src/buggy/scripts/serial/ros_to_bnyahaj.py
index 0efffb6..7a9d160 100755
--- a/rb_ws/src/buggy/scripts/serial/ros_to_bnyahaj.py
+++ b/rb_ws/src/buggy/scripts/serial/ros_to_bnyahaj.py
@@ -148,7 +148,6 @@ def set_steering(self, msg):
self.steer_angle = msg.data
self.fresh_steer = True
-
def writer_thread(self):
"""
Sends ROS Topics to bnayhaj serial, only sends a steering angle when we receive a fresh one
diff --git a/rb_ws/src/buggy/buggy/visualization/telematics.py b/rb_ws/src/buggy/scripts/visualization/telematics.py
similarity index 100%
rename from rb_ws/src/buggy/buggy/visualization/telematics.py
rename to rb_ws/src/buggy/scripts/visualization/telematics.py