Skip to content

Commit

Permalink
added env_var support
Browse files Browse the repository at this point in the history
  • Loading branch information
mehulgoel873 committed Jan 11, 2025
1 parent a380631 commit 600cf45
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 5 deletions.
3 changes: 2 additions & 1 deletion rb_ws/src/buggy/scripts/controller/controller_node.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#!/usr/bin/env python3

import os
import threading
import numpy as np
import rclpy
Expand Down Expand Up @@ -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)

Expand Down
7 changes: 3 additions & 4 deletions rb_ws/src/buggy/scripts/path_planner/path_planner.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3

import sys
import os
from threading import Lock

import numpy as np
Expand All @@ -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):
Expand Down Expand Up @@ -53,15 +52,15 @@ 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
curb_name = None if curb_name == "" else curb_name
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)
Expand Down
1 change: 1 addition & 0 deletions rb_ws/src/buggy/scripts/simulator/engine.py
Original file line number Diff line number Diff line change
@@ -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
Expand Down

0 comments on commit 600cf45

Please sign in to comment.