Skip to content

Commit

Permalink
added env vars (in yaml not in env.dev)
Browse files Browse the repository at this point in the history
  • Loading branch information
TiaSinghania committed Jan 10, 2025
1 parent 58bc706 commit ad11394
Show file tree
Hide file tree
Showing 6 changed files with 9 additions and 12 deletions.
3 changes: 3 additions & 0 deletions .env.dev
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,6 @@ WEBCAM_PORT=/dev/null
RLSENSE_PORT=/dev/null
TEENSY_PORT=/dev/null
FEATHER_PORT=/dev/null
ROOT_DIR="/rb_ws/src/buggy"
SCRIPTS_DIR="$ROOT_DIR/buggy"

4 changes: 4 additions & 0 deletions docker-dev.yml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,12 @@ services:
- "${FEATHER_PORT:-/dev/null}:/dev/ttyACM1"
stdin_open: true # docker run -i
tty: true # docker run -t
env_file: .env.dev
environment:
- DISPLAY=host.docker.internal:0
- ROOT_DIR=${ROOT_DIR:-/rb_ws/src/buggy}
- SCRIPTS_DIR=${SCRIPTS_DIR:-/rb_ws/src/buggy/buggy}
- PYTHONPATH=${SCRIPTS_DIR:-/rb_ws/src/buggy/buggy}
hostname: main
ports:
- "0.0.0.0:8765:8765" # foxglove bridge
Expand Down
6 changes: 1 addition & 5 deletions rb_ws/src/buggy/buggy/controller/controller_node.py
Original file line number Diff line number Diff line change
@@ -1,15 +1,11 @@
import threading
import sys

import numpy as np

import rclpy
from rclpy.node import Node

from std_msgs.msg import Float32, Float64, Bool
from nav_msgs.msg import Odometry

sys.path.append("/rb_ws/src/buggy/buggy")
from util.trajectory import Trajectory
from controller.stanley_controller import StanleyController

Expand All @@ -21,7 +17,7 @@ def __init__(self):
Creates a ROS node with a publisher that periodically sends a message
indicating whether the node is still alive.
"""
super().__init__('controller')
self.get_logger().info('INITIALIZED.')
Expand Down
2 changes: 0 additions & 2 deletions rb_ws/src/buggy/buggy/controller/controller_superclass.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
from abc import ABC, abstractmethod
import sys

from nav_msgs.msg import Odometry


sys.path.append("/rb_ws/src/buggy/buggy")
from util.trajectory import Trajectory

class Controller(ABC):
Expand Down
2 changes: 0 additions & 2 deletions rb_ws/src/buggy/buggy/controller/stanley_controller.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,9 @@
import sys
import numpy as np

from sensor_msgs.msg import NavSatFix
from geometry_msgs.msg import Pose as ROSPose
from nav_msgs.msg import Odometry

sys.path.append("/rb_ws/src/buggy/buggy")
from util.trajectory import Trajectory
from controller.controller_superclass import Controller
from util.pose import Pose
Expand Down
4 changes: 1 addition & 3 deletions rb_ws/src/buggy/buggy/simulator/engine.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#! /usr/bin/env python3
import threading
import sys

import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Pose, Twist, PoseWithCovariance, TwistWithCovariance
Expand All @@ -9,7 +9,6 @@
from nav_msgs.msg import Odometry
import numpy as np
import utm
sys.path.append("/rb_ws/src/buggy/buggy")
from util.constants import Constants

class Simulator(Node):
Expand All @@ -19,7 +18,6 @@ def __init__(self):
super().__init__('sim_single')
self.get_logger().info('INITIALIZED.')


self.starting_poses = {
"Hill1_NAND": (Constants.UTM_EAST_ZERO + 0, Constants.UTM_NORTH_ZERO + 0, -110),
"Hill1_SC": (Constants.UTM_EAST_ZERO + 20, Constants.UTM_NORTH_ZERO + 30, -110),
Expand Down

0 comments on commit ad11394

Please sign in to comment.