diff --git a/.env.dev b/.env.dev index baed5be..8f6619e 100755 --- a/.env.dev +++ b/.env.dev @@ -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" + diff --git a/docker-dev.yml b/docker-dev.yml index 65470a1..c2000e5 100755 --- a/docker-dev.yml +++ b/docker-dev.yml @@ -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 diff --git a/rb_ws/src/buggy/buggy/controller/controller_node.py b/rb_ws/src/buggy/buggy/controller/controller_node.py index 9d13593..df1b418 100644 --- a/rb_ws/src/buggy/buggy/controller/controller_node.py +++ b/rb_ws/src/buggy/buggy/controller/controller_node.py @@ -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 @@ -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.') diff --git a/rb_ws/src/buggy/buggy/controller/controller_superclass.py b/rb_ws/src/buggy/buggy/controller/controller_superclass.py index f960de7..905d606 100644 --- a/rb_ws/src/buggy/buggy/controller/controller_superclass.py +++ b/rb_ws/src/buggy/buggy/controller/controller_superclass.py @@ -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): diff --git a/rb_ws/src/buggy/buggy/controller/stanley_controller.py b/rb_ws/src/buggy/buggy/controller/stanley_controller.py index 3407653..b5f69ca 100644 --- a/rb_ws/src/buggy/buggy/controller/stanley_controller.py +++ b/rb_ws/src/buggy/buggy/controller/stanley_controller.py @@ -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 diff --git a/rb_ws/src/buggy/buggy/simulator/engine.py b/rb_ws/src/buggy/buggy/simulator/engine.py index 6c7e7ad..b6047f1 100644 --- a/rb_ws/src/buggy/buggy/simulator/engine.py +++ b/rb_ws/src/buggy/buggy/simulator/engine.py @@ -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 @@ -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): @@ -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),