diff --git a/.gitignore b/.gitignore
index f3fcd37e..88667fbf 100644
--- a/.gitignore
+++ b/.gitignore
@@ -1,10 +1,15 @@
.DS_Store
-rb_ws/bags
.docker-compose.yml.un~
.python-requirements.txt.un~
docker-compose.yml~
*TEMP_DO_NOT_EDIT.txt
-rb_ws/src/buggy/bags/
+
+# BAGS
+rb_ws/bags
+rb_ws/src/buggy/bags/*
*.bag
+rb_ws/rosbag2/
+
+# VISION
.vision/
-vision/data/
\ No newline at end of file
+vision/data/
diff --git a/Dockerfile b/Dockerfile
index 6725e778..4ffeb8de 100644
--- a/Dockerfile
+++ b/Dockerfile
@@ -23,16 +23,8 @@ RUN pip3 install -r python-requirements.txt
RUN echo 'source "/opt/ros/humble/setup.bash" --' >> ~/.bashrc && \
echo 'cd rb_ws' >> ~/.bashrc && \
echo 'colcon build --symlink-install' >> ~/.bashrc && \
- echo 'source install/local_setup.bash' >> ~/.bashrc
-# RUN echo 'source "/opt/ros/humble/setup.bash" --' >> ~/.bashrc && \
-# echo 'cd rb_ws' >> ~/.bashrc && \
-# echo 'catkin_make >/dev/null' >> ~/.bashrc && \
-# echo 'source devel/setup.bash' >> ~/.bashrc
-
-
-
-# RUN echo "exec firefox" > ~/.xinitrc && chmod +x ~/.xinitrc
-# CMD ["x11vnc", "-create", "-forever"]
+ echo 'source install/local_setup.bash' >> ~/.bashrc && \
+ echo 'chmod -R +x src/buggy/scripts/' >> ~/.bashrc
# add mouse to tmux
RUN echo 'set -g mouse on' >> ~/.tmux.conf
diff --git a/rb_ws/src/buggy/CMakeLists.txt b/rb_ws/src/buggy/CMakeLists.txt
new file mode 100644
index 00000000..a8a51421
--- /dev/null
+++ b/rb_ws/src/buggy/CMakeLists.txt
@@ -0,0 +1,48 @@
+cmake_minimum_required(VERSION 3.8)
+project(buggy)
+
+# Default to C++14
+if(NOT CMAKE_CXX_STANDARD)
+ set(CMAKE_CXX_STANDARD 14)
+endif()
+
+if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+ add_compile_options(-Wall -Wextra -Wpedantic)
+endif()
+
+# Find dependencies
+find_package(ament_cmake REQUIRED)
+find_package(ament_cmake_python REQUIRED)
+find_package(rclcpp REQUIRED)
+find_package(rclpy REQUIRED)
+
+# Install Launch Files
+install(DIRECTORY
+ launch
+ DESTINATION share/${PROJECT_NAME}
+)
+
+# Install Python modules
+# ament_python_install_package(${PROJECT_NAME})
+
+# Install Python executables
+install(PROGRAMS
+ scripts/hello_world.py
+ scripts/controller/controller_node.py
+ scripts/path_planner/path_planner.py
+ scripts/simulator/engine.py
+ scripts/watchdog/watchdog_node.py
+ scripts/buggy_state_converter.py
+ scripts/serial/ros_to_bnyahaj.py
+ DESTINATION lib/${PROJECT_NAME}
+)
+
+
+find_package(rosidl_default_generators REQUIRED)
+
+rosidl_generate_interfaces(${PROJECT_NAME}
+ "msg/TrajectoryMsg.msg"
+)
+ament_export_dependencies(rosidl_default_runtime)
+
+ament_package()
\ No newline at end of file
diff --git a/rb_ws/src/buggy/launch/controller.xml b/rb_ws/src/buggy/launch/controller.xml
deleted file mode 100644
index 52f0ac7f..00000000
--- a/rb_ws/src/buggy/launch/controller.xml
+++ /dev/null
@@ -1,4 +0,0 @@
-
-
-
-
\ No newline at end of file
diff --git a/rb_ws/src/buggy/launch/sim_2d_double.xml b/rb_ws/src/buggy/launch/sim_2d_double.xml
new file mode 100644
index 00000000..b9d5ba61
--- /dev/null
+++ b/rb_ws/src/buggy/launch/sim_2d_double.xml
@@ -0,0 +1,31 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ 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 2c62b1b1..f0e72042 100755
--- a/rb_ws/src/buggy/launch/sim_2d_single.xml
+++ b/rb_ws/src/buggy/launch/sim_2d_single.xml
@@ -2,23 +2,14 @@
-
+
-
-
+
+
-
-
-
-
\ No newline at end of file
diff --git a/rb_ws/src/buggy/launch/watchdog.xml b/rb_ws/src/buggy/launch/watchdog.xml
index 28c784df..5c74690e 100644
--- a/rb_ws/src/buggy/launch/watchdog.xml
+++ b/rb_ws/src/buggy/launch/watchdog.xml
@@ -1,4 +1,4 @@
-
+
\ No newline at end of file
diff --git a/rb_ws/src/buggy/package.xml b/rb_ws/src/buggy/package.xml
index e1471e2c..26879e3d 100644
--- a/rb_ws/src/buggy/package.xml
+++ b/rb_ws/src/buggy/package.xml
@@ -2,18 +2,30 @@
buggy
- 0.0.0
- TODO: Package description
- root
- TODO: License declaration
+ 2.0.0
+ CMU's First Robotic Buggy
+ CMU's Robotic Club Officers
+ MIT
+
+ ament_cmake
+ ament_cmake_python
+
+
+ rclcpp
+ rclpy
+
- ament_copyright
- ament_flake8
- ament_pep257
- python3-pytest
ros2launch
+ ament_lint_auto
+ ament_lint_common
+
+ rosidl_default_generators
+ rosidl_default_runtime
+ rosidl_interface_packages
+
+
- ament_python
+ ament_cmake
-
+
\ No newline at end of file
diff --git a/rb_ws/src/buggy/resource/buggy b/rb_ws/src/buggy/resource/buggy
deleted file mode 100644
index e69de29b..00000000
diff --git a/rb_ws/src/buggy/buggy/buggy_state_converter.py b/rb_ws/src/buggy/scripts/buggy_state_converter.py
old mode 100644
new mode 100755
similarity index 100%
rename from rb_ws/src/buggy/buggy/buggy_state_converter.py
rename to rb_ws/src/buggy/scripts/buggy_state_converter.py
diff --git a/rb_ws/src/buggy/buggy/controller/controller_node.py b/rb_ws/src/buggy/scripts/controller/controller_node.py
old mode 100644
new mode 100755
similarity index 95%
rename from rb_ws/src/buggy/buggy/controller/controller_node.py
rename to rb_ws/src/buggy/scripts/controller/controller_node.py
index 9d13593c..3094ca84
--- a/rb_ws/src/buggy/buggy/controller/controller_node.py
+++ b/rb_ws/src/buggy/scripts/controller/controller_node.py
@@ -1,3 +1,5 @@
+#!/usr/bin/env python3
+
import threading
import sys
@@ -8,8 +10,9 @@
from std_msgs.msg import Float32, Float64, Bool
from nav_msgs.msg import Odometry
+from buggy.msg import TrajectoryMsg
-sys.path.append("/rb_ws/src/buggy/buggy")
+sys.path.append("/rb_ws/src/buggy/scripts")
from util.trajectory import Trajectory
from controller.stanley_controller import StanleyController
@@ -55,12 +58,12 @@ def __init__(self):
Float64, "input/steering", 1
)
self.heading_publisher = self.create_publisher(
- Float32, "auton/debug/heading", 1
+ Float32, "debug/heading", 1
)
# Subscribers
self.odom_subscriber = self.create_subscription(Odometry, 'self/state', self.odom_listener, 1)
- self.traj_subscriber = self.create_subscription(Odometry, 'self/cur_traj', self.traj_listener, 1)
+ self.traj_subscriber = self.create_subscription(TrajectoryMsg, 'self/cur_traj', self.traj_listener, 1)
self.lock = threading.Lock()
@@ -139,7 +142,7 @@ def loop(self):
self.heading_publisher.publish(Float32(data=np.rad2deg(self.odom.pose.pose.orientation.z)))
steering_angle = self.controller.compute_control(self.odom, self.cur_traj)
steering_angle_deg = np.rad2deg(steering_angle)
- self.steer_publisher.publish(Float64(data=float(steering_angle_deg)))
+ self.steer_publisher.publish(Float64(data=float(steering_angle_deg.item())))
diff --git a/rb_ws/src/buggy/buggy/controller/controller_superclass.py b/rb_ws/src/buggy/scripts/controller/controller_superclass.py
old mode 100644
new mode 100755
similarity index 96%
rename from rb_ws/src/buggy/buggy/controller/controller_superclass.py
rename to rb_ws/src/buggy/scripts/controller/controller_superclass.py
index f960de75..731c96ee
--- a/rb_ws/src/buggy/buggy/controller/controller_superclass.py
+++ b/rb_ws/src/buggy/scripts/controller/controller_superclass.py
@@ -4,7 +4,7 @@
from nav_msgs.msg import Odometry
-sys.path.append("/rb_ws/src/buggy/buggy")
+sys.path.append("/rb_ws/src/buggy/scripts")
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/scripts/controller/stanley_controller.py
old mode 100644
new mode 100755
similarity index 97%
rename from rb_ws/src/buggy/buggy/controller/stanley_controller.py
rename to rb_ws/src/buggy/scripts/controller/stanley_controller.py
index 34076535..ce9b8113
--- a/rb_ws/src/buggy/buggy/controller/stanley_controller.py
+++ b/rb_ws/src/buggy/scripts/controller/stanley_controller.py
@@ -5,7 +5,7 @@
from geometry_msgs.msg import Pose as ROSPose
from nav_msgs.msg import Odometry
-sys.path.append("/rb_ws/src/buggy/buggy")
+sys.path.append("/rb_ws/src/buggy/scripts")
from util.trajectory import Trajectory
from controller.controller_superclass import Controller
from util.pose import Pose
@@ -30,10 +30,10 @@ class StanleyController(Controller):
def __init__(self, start_index, namespace, node):
super(StanleyController, self).__init__(start_index, namespace, node)
self.debug_reference_pos_publisher = self.node.create_publisher(
- NavSatFix, "auton/debug/reference_navsat", 1
+ NavSatFix, "controller/debug/reference_navsat", 1
)
self.debug_error_publisher = self.node.create_publisher(
- ROSPose, "auton/debug/error", 1
+ ROSPose, "controller/debug/stanley_error", 1
)
def compute_control(self, state_msg : Odometry, trajectory : Trajectory):
diff --git a/rb_ws/src/buggy/buggy/hello_world.py b/rb_ws/src/buggy/scripts/hello_world.py
old mode 100644
new mode 100755
similarity index 50%
rename from rb_ws/src/buggy/buggy/hello_world.py
rename to rb_ws/src/buggy/scripts/hello_world.py
index 0a119aa0..0a2d9ba7
--- a/rb_ws/src/buggy/buggy/hello_world.py
+++ b/rb_ws/src/buggy/scripts/hello_world.py
@@ -1,5 +1,7 @@
+#!/usr/bin/env python3
+
def main():
- print('Hi from buggy. Hello again')
+ print('Hi from buggy.')
if __name__ == '__main__':
diff --git a/rb_ws/src/buggy/scripts/path_planner/path_planner.py b/rb_ws/src/buggy/scripts/path_planner/path_planner.py
new file mode 100755
index 00000000..a42e6a1d
--- /dev/null
+++ b/rb_ws/src/buggy/scripts/path_planner/path_planner.py
@@ -0,0 +1,247 @@
+#!/usr/bin/env python3
+
+import sys
+from threading import Lock
+
+import numpy as np
+import rclpy
+from rclpy.node import Node
+
+from nav_msgs.msg import Odometry
+from std_msgs.msg import Float64
+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):
+ """
+ Class to generate new trajectory splices for SC autonomous system.
+
+ Takes in a default trajectory and an inner curb trajectory.
+
+ """
+
+ # move the curb towards the center of the course by CURB_MARGIN meters
+ # for a margin of safety
+ CURB_MARGIN = 1 #m
+
+ # the offset is calculated as a mirrored sigmoid function of distance
+ OFFSET_SCALE_CROSS_TRACK = 2 #m
+ OFFSET_SCALE_ALONG_TRACK = 0.2
+ ACTIVATE_OTHER_SCALE_ALONG_TRACK = 0.1
+ OFFSET_SHIFT_ALONG_TRACK = 4 #m
+
+ # number of meters ahead of the buggy to generate local trajectory for
+ LOCAL_TRAJ_LEN = 50#m
+
+ # start generating local trajectory this many meters ahead of current position
+ LOOKAHEAD = 2#m
+
+ # number of points to sample along the nominal trajectory
+ RESOLUTION = 150
+
+ # frequency to run in hz
+ FREQUENCY = 10
+
+ def __init__(self) -> None:
+ super().__init__('path_planner')
+ self.get_logger().info('INITIALIZED.')
+
+
+ #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.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
+
+ #Publishers
+ self.other_buggy_xtrack_publisher = self.create_publisher(Float64, "debug/other_buggy_xtrack", 10)
+ self.traj_publisher = self.create_publisher(TrajectoryMsg, "self/cur_traj", 10)
+
+ #Subscribers
+ self.self_pose_subscriber = self.create_subscription(Odometry, 'self/state', self.self_pose_callback, 1)
+ self.other_pose_subscriber = self.create_subscription(Odometry, 'other/state', self.other_pose_callback, 1)
+
+ self.timer = self.create_timer(1/self.FREQUENCY, self.timer_callback)
+
+ # set up subscriber and callback for pose variables
+ self.self_pose = None
+ self.other_pose = None
+
+ self.self_pose_lock = Lock()
+ self.other_pose_lock = Lock()
+
+ def self_pose_callback(self, msg):
+ with self.self_pose_lock:
+ self.self_pose = msg.pose.pose
+
+ def other_pose_callback(self, msg):
+ with self.other_pose_lock:
+ self.other_pose = msg.pose.pose
+ self.get_logger().debug("Received position of other buggy.")
+
+ def timer_callback(self):
+ with self.self_pose_lock and self.other_pose_lock:
+ if (self.self_pose is not None) and (self.other_pose is not None):
+ self.compute_traj(self.self_pose, self.other_pose)
+
+ def offset_func(self, dist):
+ """
+ Args:
+ dist: (N, ) numpy array, distances between ego-buggy and obstacle,
+ along the trajectory
+ Returns:
+ (N, ) numpy array, offsets from nominal trajectory required to overtake,
+ defined by a sigmoid function
+ """
+
+ return self.OFFSET_SCALE_CROSS_TRACK / \
+ (1 + np.exp(-(-self.OFFSET_SCALE_ALONG_TRACK * dist +
+ self.OFFSET_SHIFT_ALONG_TRACK)))
+
+ def activate_other_crosstrack_func(self, dist):
+ """
+ Args:
+ dist: (N, ) numpy array, distances between ego-buggy and obstacle,
+ along the trajectory
+ Returns:
+ (N, ) numpy array, multiplier used to weigh the cross-track distance of
+ the obstacle into the passing offset calculation.
+ """
+ return 1 / \
+ (1 + np.exp(-(-self.ACTIVATE_OTHER_SCALE_ALONG_TRACK * dist +
+ self.OFFSET_SHIFT_ALONG_TRACK)))
+
+
+ def compute_traj(
+ self,
+ self_pose: Pose,
+ other_pose: Pose,
+ ) -> None:
+ """
+ draw trajectory starting at the current pose and ending at a fixed distance
+ ahead. For each trajectory point, calculate the required offset perpendicular to the nominal
+ trajectory. A sigmoid function of the distance along track to the other buggy is used to
+ weigh the other buggy's cross-track distance. This calculation produces a line that
+ allows the ego-buggy's trajectory to go through the other buggy. Since we want to pass
+ the other buggy at some constant distance to the left, another sigmoid function is multiplied
+ by that constant distance to produce a smooth trajectory that passes the other buggy.
+
+ Finally, the trajectory is bounded to the left by the left curb (if it exists), and to the right
+ by the nominal trajectory. (we never pass on the right)
+
+ passing offsets =
+ activate_other_crosstrack_func(distance to other buggy along track) *
+ other buggy cross track distance +
+ offset_func(distance to other buggy along track)
+
+ trajectory = nominal trajectory +
+ left nominal trajectory unit normal vector *
+ clamp(passing offsets, 0, distance from nominal trajectory to left curb)
+
+ Args:
+ other_pose (Pose): Pose containing NAND's easting (x),
+ northing(y), and heading (theta), in UTM
+
+ other_speed (float): speed in m/s of NAND
+ Publishes:
+ Trajectory: list of x,y coords for ego-buggy to follow.
+ """
+ # grab slice of nominal trajectory
+ nominal_idx = self.nominal_traj.get_closest_index_on_path(self_pose.position.x, self_pose.position.y)
+ nominal_dist_along = self.nominal_traj.get_distance_from_index(nominal_idx)
+
+ nominal_slice = np.empty((self.RESOLUTION, 2))
+
+ # compute the distance along nominal trajectory between samples and the obstacle
+ nominal_slice_dists = np.linspace(
+ nominal_dist_along + self.LOOKAHEAD,
+ nominal_dist_along + self.LOOKAHEAD + self.LOCAL_TRAJ_LEN,
+ self.RESOLUTION)
+
+ for i in range(self.RESOLUTION):
+ nominal_slice[i, :] = np.array(self.nominal_traj.get_position_by_distance(
+ nominal_slice_dists[i]
+ ))
+
+ # get index of the other buggy along the trajetory and convert to distance
+ other_idx = self.nominal_traj.get_closest_index_on_path(other_pose.position.x, other_pose.position.y)
+ other_dist = self.nominal_traj.get_distance_from_index(other_idx)
+ nominal_slice_to_other_dist = np.abs(nominal_slice_dists - other_dist)
+
+ passing_offsets = self.offset_func(nominal_slice_to_other_dist)
+
+ # compute signed cross-track distance between NAND and nominal
+ nominal_to_other = np.array((other_pose.position.x, other_pose.position.y)) - \
+ np.array(self.nominal_traj.get_position_by_index(other_idx))
+
+ # dot product with the unit normal to produce left-positive signed distance
+ other_normal = self.nominal_traj.get_unit_normal_by_index(np.array(other_idx.ravel()))
+ other_cross_track_dist = np.sum(
+ nominal_to_other * other_normal, axis=1)
+
+ self.other_buggy_xtrack_publisher.publish(Float64(data=float(other_cross_track_dist.item())))
+
+ # here, use passing offsets to weight NAND's cross track signed distance:
+ # if the sample point is far from SC, the cross track distance doesn't matter
+ # if the sample point is near, we add cross track distance to the offset,
+ # such that the resulting offset is adjusted by position of NAND
+
+ passing_offsets = passing_offsets + \
+ self.activate_other_crosstrack_func(nominal_slice_to_other_dist) * other_cross_track_dist
+
+ # clamp passing offset distances to distance to the curb
+ if self.left_curb is not None:
+ # grab slice of curb correponding to slice of nominal trajectory.
+ curb_idx = self.left_curb.get_closest_index_on_path(self_pose.position.x, self_pose.position.y)
+ curb_dist_along = self.left_curb.get_distance_from_index(curb_idx)
+ curb_idx_end = self.left_curb.get_closest_index_on_path(nominal_slice[-1, 0], nominal_slice[-1, 1])
+ curb_dist_along_end = self.left_curb.get_distance_from_index(curb_idx_end)
+ curb_dists = np.linspace(curb_dist_along, curb_dist_along_end, self.RESOLUTION)
+
+ curb_slice = np.empty((self.RESOLUTION, 2))
+ for i in range(self.RESOLUTION):
+ curb_slice[i, :] = np.array(self.left_curb.get_position_by_distance(
+ curb_dists[i]
+ ))
+
+ # compute distances from the sample points to the curb
+ nominal_slice_to_curb_dist = np.linalg.norm(curb_slice - nominal_slice, axis=1)
+ passing_offsets = np.minimum(passing_offsets, nominal_slice_to_curb_dist - self.CURB_MARGIN)
+
+ # clamp negative passing offsets to zero, since we always pass on the left,
+ # the passing offsets should never pull SC to the right.
+ passing_offsets = np.maximum(0, passing_offsets)
+
+ # shift the nominal slice by passing offsets
+ nominal_normals = self.nominal_traj.get_unit_normal_by_index(
+ self.nominal_traj.get_index_from_distance(nominal_slice_dists)
+ )
+ positions = nominal_slice + (passing_offsets[:, None] * nominal_normals)
+
+ local_traj = Trajectory(json_filepath=None, positions=positions)
+ self.traj_publisher.publish(local_traj.pack(self_pose.position.x, self_pose.position.y ))
+
+
+def main(args=None):
+ rclpy.init(args=args)
+ # TODO: set file paths here
+ # At the time of writing the below snippet, config management is TBD
+
+ path_planner = PathPlanner()
+ rclpy.spin(path_planner)
+
+ path_planner.destroy_node()
+ rclpy.shutdown()
+
+if __name__ == '__main__':
+ main()
\ No newline at end of file
diff --git a/rb_ws/src/buggy/buggy/serial/host_comm.py b/rb_ws/src/buggy/scripts/serial/host_comm.py
old mode 100644
new mode 100755
similarity index 100%
rename from rb_ws/src/buggy/buggy/serial/host_comm.py
rename to rb_ws/src/buggy/scripts/serial/host_comm.py
diff --git a/rb_ws/src/buggy/buggy/serial/ros_to_bnyahaj.py b/rb_ws/src/buggy/scripts/serial/ros_to_bnyahaj.py
old mode 100644
new mode 100755
similarity index 99%
rename from rb_ws/src/buggy/buggy/serial/ros_to_bnyahaj.py
rename to rb_ws/src/buggy/scripts/serial/ros_to_bnyahaj.py
index 974ef874..0efffb61
--- a/rb_ws/src/buggy/buggy/serial/ros_to_bnyahaj.py
+++ b/rb_ws/src/buggy/scripts/serial/ros_to_bnyahaj.py
@@ -1,11 +1,13 @@
+#!/usr/bin/env python3
+
import argparse
from threading import Lock
import threading
import rclpy
-from rclpy import Node
+from host_comm import *
+from rclpy.node import Node
from std_msgs.msg import Float64, Int8, Int32, UInt8, Bool, UInt64
-from host_comm import *
from nav_msgs.msg import Odometry
class Translator(Node):
diff --git a/rb_ws/src/buggy/buggy/simulator/engine.py b/rb_ws/src/buggy/scripts/simulator/engine.py
old mode 100644
new mode 100755
similarity index 94%
rename from rb_ws/src/buggy/buggy/simulator/engine.py
rename to rb_ws/src/buggy/scripts/simulator/engine.py
index b3cb7746..af2bdc5b
--- a/rb_ws/src/buggy/buggy/simulator/engine.py
+++ b/rb_ws/src/buggy/scripts/simulator/engine.py
@@ -1,6 +1,7 @@
#! /usr/bin/env python3
import threading
import sys
+import time
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Pose, Twist, PoseWithCovariance, TwistWithCovariance
@@ -9,8 +10,9 @@
from nav_msgs.msg import Odometry
import numpy as np
import utm
-sys.path.append("/rb_ws/src/buggy/buggy")
-from rb_ws.src.buggy.buggy.util.constants import Constants
+
+sys.path.append("/rb_ws/src/buggy/scripts")
+from util.constants import Constants
class Simulator(Node):
@@ -130,7 +132,7 @@ def publish(self):
with self.lock:
p.position.x = self.e_utm
p.position.y = self.n_utm
- p.position.z = self.heading
+ p.position.z = float(self.heading)
velocity = self.velocity
self.plot_publisher.publish(p)
@@ -176,11 +178,18 @@ def loop(self):
if self.tick_count % self.interval == 0:
self.publish()
self.tick_count += 1
+ self.get_logger().debug("SIMULATED UTM: ({}, {}), HEADING: {}".format(self.e_utm, self.n_utm, self.heading))
def main(args=None):
rclpy.init(args=args)
sim = Simulator()
+ for _ in range(500):
+ time.sleep(0.01)
+ sim.publish()
+
+
+ sim.get_logger().info("STARTED PUBLISHING")
rclpy.spin(sim)
sim.destroy_node()
diff --git a/rb_ws/src/buggy/buggy/util/constants.py b/rb_ws/src/buggy/scripts/util/constants.py
old mode 100644
new mode 100755
similarity index 100%
rename from rb_ws/src/buggy/buggy/util/constants.py
rename to rb_ws/src/buggy/scripts/util/constants.py
diff --git a/rb_ws/src/buggy/buggy/util/pose.py b/rb_ws/src/buggy/scripts/util/pose.py
old mode 100644
new mode 100755
similarity index 100%
rename from rb_ws/src/buggy/buggy/util/pose.py
rename to rb_ws/src/buggy/scripts/util/pose.py
diff --git a/rb_ws/src/buggy/buggy/util/trajectory.py b/rb_ws/src/buggy/scripts/util/trajectory.py
old mode 100644
new mode 100755
similarity index 98%
rename from rb_ws/src/buggy/buggy/util/trajectory.py
rename to rb_ws/src/buggy/scripts/util/trajectory.py
index 72fbcaee..1bbdfb46
--- a/rb_ws/src/buggy/buggy/util/trajectory.py
+++ b/rb_ws/src/buggy/scripts/util/trajectory.py
@@ -1,13 +1,14 @@
import json
+import time
# from buggy.msg import TrajectoryMsg
import numpy as np
from scipy.interpolate import Akima1DInterpolator, CubicSpline
+from buggy.msg import TrajectoryMsg
import utm
-
class Trajectory:
"""A wrapper around a trajectory JSON file that does some under-the-hood math. Will
interpolate the data points and calculate other information such as distance along the trajectory
@@ -347,10 +348,10 @@ def get_closest_index_on_path(
+ start_index
)
- """ def pack(self, x, y) -> TrajectoryMsg:
+ def pack(self, x, y) -> TrajectoryMsg:
traj = TrajectoryMsg()
- traj.easting = self.positions[:, 0]
- traj.northing = self.positions[:, 1]
+ traj.easting = list(self.positions[:, 0])
+ traj.northing = list(self.positions[:, 1])
traj.time = time.time()
traj.cur_idx = self.get_closest_index_on_path(x,y)
return traj
@@ -358,5 +359,5 @@ def get_closest_index_on_path(
def unpack(trajMsg : TrajectoryMsg):
pos = np.array([trajMsg.easting, trajMsg.northing]).transpose(1, 0)
cur_idx = trajMsg.cur_idx
- return Trajectory(positions=pos), cur_idx """
+ return Trajectory(positions=pos), cur_idx
diff --git a/rb_ws/src/buggy/buggy/watchdog/watchdog_node.py b/rb_ws/src/buggy/scripts/watchdog/watchdog_node.py
old mode 100644
new mode 100755
similarity index 98%
rename from rb_ws/src/buggy/buggy/watchdog/watchdog_node.py
rename to rb_ws/src/buggy/scripts/watchdog/watchdog_node.py
index b0338da8..7c155e32
--- a/rb_ws/src/buggy/buggy/watchdog/watchdog_node.py
+++ b/rb_ws/src/buggy/scripts/watchdog/watchdog_node.py
@@ -1,3 +1,5 @@
+#!/usr/bin/env python3
+
import rclpy
from rclpy.node import Node
diff --git a/rb_ws/src/buggy/setup.cfg b/rb_ws/src/buggy/setup.cfg
deleted file mode 100644
index c2b78e07..00000000
--- a/rb_ws/src/buggy/setup.cfg
+++ /dev/null
@@ -1,4 +0,0 @@
-[develop]
-script_dir=$base/lib/buggy
-[install]
-install_scripts=$base/lib/buggy
diff --git a/rb_ws/src/buggy/setup.py b/rb_ws/src/buggy/setup.py
deleted file mode 100644
index a8a022ec..00000000
--- a/rb_ws/src/buggy/setup.py
+++ /dev/null
@@ -1,34 +0,0 @@
-from glob import glob
-import os
-
-from setuptools import find_packages, setup
-
-package_name = 'buggy'
-
-setup(
- name=package_name,
- version='0.0.0',
- packages=find_packages(exclude=['test']),
- data_files=[
- ('share/ament_index/resource_index/packages',
- ['resource/' + package_name]),
- ('share/' + package_name, ['package.xml']),
- (os.path.join("share", package_name), glob("launch/*.xml"))
- ],
- install_requires=['setuptools'],
- zip_safe=True,
- maintainer='root',
- maintainer_email='root@todo.todo',
- description='TODO: Package description',
- license='TODO: License declaration',
- tests_require=['pytest'],
- entry_points={
- 'console_scripts': [
- 'hello_world = buggy.hello_world:main',
- 'sim_single = buggy.simulator.engine:main',
- 'controller = buggy.controller.controller_node:main',
- 'buggy_state_converter = buggy.buggy_state_converter:main',
- 'watchdog = buggy.watchdog.watchdog_node:main',
- ],
- },
-)
\ No newline at end of file
diff --git a/rb_ws/src/buggy/test/test_copyright.py b/rb_ws/src/buggy/test/test_copyright.py
deleted file mode 100644
index 97a39196..00000000
--- a/rb_ws/src/buggy/test/test_copyright.py
+++ /dev/null
@@ -1,25 +0,0 @@
-# Copyright 2015 Open Source Robotics Foundation, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-from ament_copyright.main import main
-import pytest
-
-
-# Remove the `skip` decorator once the source file(s) have a copyright header
-@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
-@pytest.mark.copyright
-@pytest.mark.linter
-def test_copyright():
- rc = main(argv=['.', 'test'])
- assert rc == 0, 'Found errors'
diff --git a/rb_ws/src/buggy/test/test_flake8.py b/rb_ws/src/buggy/test/test_flake8.py
deleted file mode 100644
index 27ee1078..00000000
--- a/rb_ws/src/buggy/test/test_flake8.py
+++ /dev/null
@@ -1,25 +0,0 @@
-# Copyright 2017 Open Source Robotics Foundation, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-from ament_flake8.main import main_with_errors
-import pytest
-
-
-@pytest.mark.flake8
-@pytest.mark.linter
-def test_flake8():
- rc, errors = main_with_errors(argv=[])
- assert rc == 0, \
- 'Found %d code style errors / warnings:\n' % len(errors) + \
- '\n'.join(errors)
diff --git a/rb_ws/src/buggy/test/test_pep257.py b/rb_ws/src/buggy/test/test_pep257.py
deleted file mode 100644
index b234a384..00000000
--- a/rb_ws/src/buggy/test/test_pep257.py
+++ /dev/null
@@ -1,23 +0,0 @@
-# Copyright 2015 Open Source Robotics Foundation, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-from ament_pep257.main import main
-import pytest
-
-
-@pytest.mark.linter
-@pytest.mark.pep257
-def test_pep257():
- rc = main(argv=['.', 'test'])
- assert rc == 0, 'Found code style errors / warnings'