From 600cf45ea74e26e969b3f18611c4dd623ef4aca6 Mon Sep 17 00:00:00 2001 From: Mehul Goel Date: Fri, 10 Jan 2025 23:10:42 -0800 Subject: [PATCH] added env_var support --- rb_ws/src/buggy/scripts/controller/controller_node.py | 3 ++- rb_ws/src/buggy/scripts/path_planner/path_planner.py | 7 +++---- rb_ws/src/buggy/scripts/simulator/engine.py | 1 + 3 files changed, 6 insertions(+), 5 deletions(-) diff --git a/rb_ws/src/buggy/scripts/controller/controller_node.py b/rb_ws/src/buggy/scripts/controller/controller_node.py index 316df8a3..e52fb4bb 100755 --- a/rb_ws/src/buggy/scripts/controller/controller_node.py +++ b/rb_ws/src/buggy/scripts/controller/controller_node.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 +import os import threading import numpy as np import rclpy @@ -32,7 +33,7 @@ def __init__(self): self.declare_parameter("traj_name", "buggycourse_safe.json") traj_name = self.get_parameter("traj_name").value - self.cur_traj = Trajectory(json_filepath="/rb_ws/src/buggy/paths/" + traj_name) #TODO: Fixed filepath, not good + self.cur_traj = Trajectory(json_filepath=os.environ["TRAJPATH"] + traj_name) #TODO: Fixed filepath, not good start_index = self.cur_traj.get_index_from_distance(start_dist) diff --git a/rb_ws/src/buggy/scripts/path_planner/path_planner.py b/rb_ws/src/buggy/scripts/path_planner/path_planner.py index a42e6a1d..b43d40a0 100755 --- a/rb_ws/src/buggy/scripts/path_planner/path_planner.py +++ b/rb_ws/src/buggy/scripts/path_planner/path_planner.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -import sys +import os from threading import Lock import numpy as np @@ -12,7 +12,6 @@ from geometry_msgs.msg import Pose from buggy.msg import TrajectoryMsg -sys.path.append("/rb_ws/src/buggy/scripts") from util.trajectory import Trajectory class PathPlanner(Node): @@ -53,7 +52,7 @@ def __init__(self) -> None: #Parameters self.declare_parameter("traj_name", "buggycourse_safe.json") traj_name = self.get_parameter("traj_name").value - self.nominal_traj = Trajectory(json_filepath="/rb_ws/src/buggy/paths/" + traj_name) #TODO: Fixed filepath, not good + self.nominal_traj = Trajectory(json_filepath=os.environ["TRAJPATH"] + traj_name) #TODO: Fixed filepath, not good self.declare_parameter("curb_name", "") curb_name = self.get_parameter("curb_name").value @@ -61,7 +60,7 @@ def __init__(self) -> None: if curb_name is None: self.left_curb = None else: - self.left_curb = Trajectory(json_filepath="/rb_ws/src/buggy/paths/" + curb_name) #TODO: Fixed filepath, not good + self.left_curb = Trajectory(json_filepath=os.environ["TRAJPATH"] + curb_name) #TODO: Fixed filepath, not good #Publishers self.other_buggy_xtrack_publisher = self.create_publisher(Float64, "debug/other_buggy_xtrack", 10) diff --git a/rb_ws/src/buggy/scripts/simulator/engine.py b/rb_ws/src/buggy/scripts/simulator/engine.py index 25694e7d..0b802ef1 100755 --- a/rb_ws/src/buggy/scripts/simulator/engine.py +++ b/rb_ws/src/buggy/scripts/simulator/engine.py @@ -1,6 +1,7 @@ #! /usr/bin/env python3 import threading import rclpy +import time from rclpy.node import Node from geometry_msgs.msg import Pose, Twist, PoseWithCovariance, TwistWithCovariance from std_msgs.msg import Float64