diff --git a/.github/ISSUE_TEMPLATE/BUG.yml b/.github/ISSUE_TEMPLATE/BUG.yml
index aee5410c..0bdbe38e 100644
--- a/.github/ISSUE_TEMPLATE/BUG.yml
+++ b/.github/ISSUE_TEMPLATE/BUG.yml
@@ -35,13 +35,6 @@ body:
- The car detects traffic lights on Map1 correctly.
- The issue no longer occurs in similar scenarios.
- - type: input
- id: effort_estimate
- attributes:
- label: Effort Estimate
- description: Approximate effort required (e.g., hours).
- placeholder: Enter effort estimate.
-
- type: textarea
id: testability
attributes:
@@ -59,12 +52,6 @@ body:
- type: markdown
attributes:
value: |
- **Add Priority Label**:
- - p1: Immediate attention
- - p2: High priority
- - p3: Standard priority
- - p4: Low priority
-
**Add Group Label**:
- perception: Related to sensor processing and scene understanding
- planning: Related to path planning and decision making
@@ -72,3 +59,18 @@ body:
- system: Related to the general behavior of the system
- research: Related to research and experimentation
- infrastructure: Related to system infrastructure and setup
+
+ **Add Labels on the Project Board**:
+ **Priority:**
+ - `Urgent`: Critical bug causing system crash, needs immediate fix.
+ - `High`: Major feature request or significant bug affecting many users.
+ - `Medium`: Minor feature request or bug with a workaround.
+ - `Low`: Cosmetic changes or minor improvements.
+
+ **Size:**
+ - `Tiny`: Small typo fix or minor code refactor. Estimated time: 30 minutes.
+ - `Small`: Simple bug fix or small feature addition. Estimated time: 1-2 hours.
+ - `Medium`: Moderate feature addition or multiple bug fixes. Estimated time: 1-2 days.
+ - `Large`: Major feature implementation or significant refactor. Estimated time: 1-2 weeks.
+ - `X-Large`: Large-scale feature or complete module overhaul. Estimated time: 2-4 weeks. Especially `EPIC` issues should
+ be tagged with this size.
diff --git a/.github/ISSUE_TEMPLATE/FEATURE.yml b/.github/ISSUE_TEMPLATE/FEATURE.yml
index 366bab21..bdb42505 100644
--- a/.github/ISSUE_TEMPLATE/FEATURE.yml
+++ b/.github/ISSUE_TEMPLATE/FEATURE.yml
@@ -19,13 +19,6 @@ body:
- Detects 90% of traffic lights.
- Correctly identifies 90% of traffic light states.
- - type: input
- id: effort_estimate
- attributes:
- label: Effort Estimate
- description: Approximate effort required (e.g., hours).
- placeholder: Enter effort estimate.
-
- type: textarea
id: testability
attributes:
@@ -43,11 +36,6 @@ body:
- type: markdown
attributes:
value: |
- **Add Priority Label**:
- - p1: Immediate attention
- - p2: High priority
- - p3: Standard priority
- - p4: Low priority
**Add Group Label**:
- perception: Related to sensor processing and scene understanding
@@ -56,3 +44,18 @@ body:
- system: Related to the general behavior of the system
- research: Related to research and experimentation
- infrastructure: Related to system infrastructure and setup
+
+ **Add Labels on the Project Board**:
+ **Priority:**
+ - `Urgent`: Critical bug causing system crash, needs immediate fix.
+ - `High`: Major feature request or significant bug affecting many users.
+ - `Medium`: Minor feature request or bug with a workaround.
+ - `Low`: Cosmetic changes or minor improvements.
+
+ **Size:**
+ - `Tiny`: Small typo fix or minor code refactor. Estimated time: 30 minutes.
+ - `Small`: Simple bug fix or small feature addition. Estimated time: 1-2 hours.
+ - `Medium`: Moderate feature addition or multiple bug fixes. Estimated time: 1-2 days.
+ - `Large`: Major feature implementation or significant refactor. Estimated time: 1-2 weeks.
+ - `X-Large`: Large-scale feature or complete module overhaul. Estimated time: 2-4 weeks. Especially `EPIC` issues should
+ be tagged with this size.
diff --git a/.github/ISSUE_TEMPLATE/ISSUE.yml b/.github/ISSUE_TEMPLATE/ISSUE.yml
index 6ad88fbf..e5cbc82c 100644
--- a/.github/ISSUE_TEMPLATE/ISSUE.yml
+++ b/.github/ISSUE_TEMPLATE/ISSUE.yml
@@ -25,13 +25,6 @@ body:
- Code review passed
- All tests passing
- - type: input
- id: effort_estimate
- attributes:
- label: Effort Estimate
- description: Approximate effort required (e.g., hours).
- placeholder: Enter effort estimate.
-
- type: textarea
id: testability
attributes:
@@ -58,12 +51,6 @@ body:
- question: Further information is requested
- wontfix: This will not be worked on
- **Add Priority Label**:
- - p1: Immediate attention
- - p2: High priority
- - p3: Standard priority
- - p4: Low priority
-
**Add Group Label**:
- perception: Related to sensor processing and scene understanding
- planning: Related to path planning and decision making
@@ -71,3 +58,18 @@ body:
- system: Related to the general behavior of the system
- research: Related to research and experimentation
- infrastructure: Related to system infrastructure and setup
+
+ **Add Labels on the Project Board**:
+ **Priority:**
+ - `Urgent`: Critical bug causing system crash, needs immediate fix.
+ - `High`: Major feature request or significant bug affecting many users.
+ - `Medium`: Minor feature request or bug with a workaround.
+ - `Low`: Cosmetic changes or minor improvements.
+
+ **Size:**
+ - `Tiny`: Small typo fix or minor code refactor. Estimated time: 30 minutes.
+ - `Small`: Simple bug fix or small feature addition. Estimated time: 1-2 hours.
+ - `Medium`: Moderate feature addition or multiple bug fixes. Estimated time: 1-2 days.
+ - `Large`: Major feature implementation or significant refactor. Estimated time: 1-2 weeks.
+ - `X-Large`: Large-scale feature or complete module overhaul. Estimated time: 2-4 weeks. Especially `EPIC` issues should
+ be tagged with this size.
diff --git a/code/acting/launch/acting.launch b/code/acting/launch/acting.launch
index 5855c9fb..25e6ddce 100644
--- a/code/acting/launch/acting.launch
+++ b/code/acting/launch/acting.launch
@@ -1,41 +1,21 @@
-
+
-
-
-
-
-
-
-
+
+
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
\ No newline at end of file
diff --git a/code/acting/src/acting/MainFramePublisher.py b/code/acting/src/acting/MainFramePublisher.py
index a34240e8..50fb47c7 100755
--- a/code/acting/src/acting/MainFramePublisher.py
+++ b/code/acting/src/acting/MainFramePublisher.py
@@ -1,6 +1,4 @@
#!/usr/bin/env python
-
-from math import pi, cos, sin
import ros_compatibility as roscomp
import rospy
from geometry_msgs.msg import PoseStamped
@@ -9,6 +7,8 @@
from scipy.spatial.transform import Rotation as R
from std_msgs.msg import Float32
+import numpy as np
+
class MainFramePublisher(CompatibleNode):
@@ -49,27 +49,28 @@ def loop(timer_event=None):
if self.current_pos is None:
# conversion only works if pos is known
return
- rot = -self.current_heading
- pos = [0, 0, 0]
- pos[0] = (
- cos(rot) * self.current_pos.pose.position.x
- - sin(rot) * self.current_pos.pose.position.y
- )
- pos[1] = (
- sin(rot) * self.current_pos.pose.position.x
- + cos(rot) * self.current_pos.pose.position.y
+
+ # The following converts the current_pos as well as the current_heading
+ # messages we receive into tf transforms.
+
+ position = np.array(
+ [
+ self.current_pos.pose.position.x,
+ self.current_pos.pose.position.y,
+ self.current_pos.pose.position.z,
+ ]
)
- pos[2] = -self.current_pos.pose.position.z
- rot_quat = R.from_euler(
- "xyz", [0, 0, -self.current_heading + pi], degrees=False
- ).as_quat()
+ rotation = R.from_euler("z", self.current_heading, degrees=False).as_quat()
+
+ # The position and rotation are "the hero frame in global coordinates"
+ # Therefore we publish the child hero with respect to the parent global
br.sendTransform(
- pos,
- rot_quat,
- rospy.Time.now(),
- "global",
- "hero",
+ translation=position,
+ rotation=rotation,
+ time=rospy.Time.now(),
+ child="hero",
+ parent="global",
)
self.new_timer(self.control_loop_rate, loop)
diff --git a/code/acting/src/acting/passthrough.py b/code/acting/src/acting/passthrough.py
new file mode 100755
index 00000000..3d49d207
--- /dev/null
+++ b/code/acting/src/acting/passthrough.py
@@ -0,0 +1,87 @@
+#!/usr/bin/env python
+
+import ros_compatibility as roscomp
+from ros_compatibility.node import CompatibleNode
+from rospy import Publisher, Subscriber
+from std_msgs.msg import Float32
+from geometry_msgs.msg import PoseStamped
+from nav_msgs.msg import Path
+
+
+from dataclasses import dataclass
+from typing import Type, Dict
+
+
+@dataclass
+class TopicMapping:
+ pub_name: str
+ sub_name: str
+ topic_type: Type
+
+
+class Passthrough(CompatibleNode):
+ """This nodes sole purpose is to pass through all messages that control needs.
+ The purpose of this is that Control-Package should not have any global dependencies,
+ but is only dependent on the acting package.
+ """
+
+ role_name = "hero" # Legacy will change soon
+
+ # Topics for velocity controller.
+ target_velocity = TopicMapping(
+ pub_name="/paf/acting/target_velocity",
+ sub_name=f"/paf/{role_name}/target_velocity",
+ topic_type=Float32,
+ )
+ # Topics for steering controllers
+ trajectory = TopicMapping(
+ pub_name="/paf/acting/trajectory",
+ sub_name=f"/paf/{role_name}/trajectory",
+ topic_type=Path,
+ )
+ position = TopicMapping(
+ pub_name="/paf/acting/current_pos",
+ sub_name=f"/paf/{role_name}/current_pos",
+ topic_type=PoseStamped,
+ )
+ heading = TopicMapping(
+ pub_name="/paf/acting/current_heading",
+ sub_name=f"/paf/{role_name}/current_heading",
+ topic_type=Float32,
+ )
+
+ mapped_topics = [target_velocity, trajectory, position, heading]
+
+ def __init__(self):
+ self.publishers: Dict[str, Publisher] = {}
+ self.subscribers: Dict[str, Subscriber] = {}
+ for topic in self.mapped_topics:
+ self.publishers[topic.pub_name] = self.new_publisher(
+ topic.topic_type, topic.pub_name, qos_profile=1
+ )
+
+ self.subscribers[topic.pub_name] = self.new_subscription(
+ topic.topic_type,
+ topic.sub_name,
+ callback=self.publishers[topic.pub_name].publish,
+ qos_profile=1,
+ )
+
+
+def main(args=None):
+ """Start the node.
+ This is the entry point, if called by a launch file.
+ """
+ roscomp.init("passthrough", args=args)
+
+ try:
+ node = Passthrough()
+ node.spin()
+ except KeyboardInterrupt:
+ pass
+ finally:
+ roscomp.shutdown()
+
+
+if __name__ == "__main__":
+ main()
diff --git a/code/control/CMakeLists.txt b/code/control/CMakeLists.txt
new file mode 100644
index 00000000..a3c31c0e
--- /dev/null
+++ b/code/control/CMakeLists.txt
@@ -0,0 +1,18 @@
+cmake_minimum_required(VERSION 3.0.2)
+project(control)
+
+
+find_package(catkin REQUIRED)
+
+catkin_python_setup()
+
+find_package(catkin REQUIRED COMPONENTS
+ rospy
+ std_msgs
+)
+catkin_package()
+
+
+include_directories(
+)
+
diff --git a/code/control/launch/control.launch b/code/control/launch/control.launch
new file mode 100644
index 00000000..88a55e26
--- /dev/null
+++ b/code/control/launch/control.launch
@@ -0,0 +1,28 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/code/control/package.xml b/code/control/package.xml
new file mode 100644
index 00000000..9aa803d6
--- /dev/null
+++ b/code/control/package.xml
@@ -0,0 +1,22 @@
+
+
+ control
+ 0.0.0
+ The control package for PAF Carla
+
+ Vinzenz Malke
+
+
+
+
+
+ TODO
+
+
+ message_runtime
+ catkin
+
+
+
+
+
\ No newline at end of file
diff --git a/code/control/setup.py b/code/control/setup.py
new file mode 100644
index 00000000..a712859a
--- /dev/null
+++ b/code/control/setup.py
@@ -0,0 +1,6 @@
+#!/usr/bin/env python
+from distutils.core import setup
+from catkin_pkg.python_setup import generate_distutils_setup
+
+setup_args = generate_distutils_setup(packages=["control"], package_dir={"": "src"})
+setup(**setup_args)
diff --git a/code/control/src/__init__.py b/code/control/src/__init__.py
new file mode 100644
index 00000000..e69de29b
diff --git a/code/acting/src/acting/pure_pursuit_controller.py b/code/control/src/pure_pursuit_controller.py
similarity index 97%
rename from code/acting/src/acting/pure_pursuit_controller.py
rename to code/control/src/pure_pursuit_controller.py
index 4259fe78..fbf6526b 100755
--- a/code/acting/src/acting/pure_pursuit_controller.py
+++ b/code/control/src/pure_pursuit_controller.py
@@ -11,7 +11,7 @@
from acting.msg import Debug
import numpy as np
-from helper_functions import vector_angle, points_to_vector
+from acting.helper_functions import vector_angle, points_to_vector
# Tuneable Values for PurePursuit-Algorithm
K_LAD = 0.85 # optimal in dev-launch
@@ -33,12 +33,12 @@ def __init__(self):
self.role_name = self.get_param("role_name", "ego_vehicle")
self.position_sub: Subscriber = self.new_subscription(
- Path, f"/paf/{self.role_name}/trajectory", self.__set_path, qos_profile=1
+ Path, "/paf/acting/trajectory", self.__set_path, qos_profile=1
)
self.path_sub: Subscriber = self.new_subscription(
PoseStamped,
- f"/paf/{self.role_name}/current_pos",
+ "/paf/acting/current_pos",
self.__set_position,
qos_profile=1,
)
@@ -52,7 +52,7 @@ def __init__(self):
self.heading_sub: Subscriber = self.new_subscription(
Float32,
- f"/paf/{self.role_name}/current_heading",
+ "/paf/acting/current_heading",
self.__set_heading,
qos_profile=1,
)
diff --git a/code/acting/src/acting/stanley_controller.py b/code/control/src/stanley_controller.py
similarity index 97%
rename from code/acting/src/acting/stanley_controller.py
rename to code/control/src/stanley_controller.py
index 3463e90e..86b26221 100755
--- a/code/acting/src/acting/stanley_controller.py
+++ b/code/control/src/stanley_controller.py
@@ -12,7 +12,7 @@
from std_msgs.msg import Float32
from acting.msg import StanleyDebug
-from helper_functions import vector_angle, points_to_vector
+from acting.helper_functions import vector_angle, points_to_vector
K_CROSSERR = 0.4 # 1.24 was optimal in dev-launch!
@@ -28,12 +28,12 @@ def __init__(self):
# Subscribers
self.position_sub: Subscriber = self.new_subscription(
- Path, f"/paf/{self.role_name}/trajectory", self.__set_path, qos_profile=1
+ Path, "/paf/acting/trajectory", self.__set_path, qos_profile=1
)
self.path_sub: Subscriber = self.new_subscription(
PoseStamped,
- f"/paf/{self.role_name}/current_pos",
+ "/paf/acting/current_pos",
self.__set_position,
qos_profile=1,
)
@@ -47,7 +47,7 @@ def __init__(self):
self.heading_sub: Subscriber = self.new_subscription(
Float32,
- f"/paf/{self.role_name}/current_heading",
+ "/paf/acting/current_heading",
self.__set_heading,
qos_profile=1,
)
diff --git a/code/acting/src/acting/vehicle_controller.py b/code/control/src/vehicle_controller.py
similarity index 100%
rename from code/acting/src/acting/vehicle_controller.py
rename to code/control/src/vehicle_controller.py
diff --git a/code/acting/src/acting/velocity_controller.py b/code/control/src/velocity_controller.py
similarity index 98%
rename from code/acting/src/acting/velocity_controller.py
rename to code/control/src/velocity_controller.py
index db1f53aa..a863748c 100755
--- a/code/acting/src/acting/velocity_controller.py
+++ b/code/control/src/velocity_controller.py
@@ -23,7 +23,7 @@ def __init__(self):
self.target_velocity_sub: Subscriber = self.new_subscription(
Float32,
- f"/paf/{self.role_name}/target_velocity",
+ "/paf/acting/target_velocity",
self.__get_target_velocity,
qos_profile=1,
)
diff --git a/code/perception/launch/perception.launch b/code/perception/launch/perception.launch
index 10f79a80..67a9c2ab 100644
--- a/code/perception/launch/perception.launch
+++ b/code/perception/launch/perception.launch
@@ -79,4 +79,10 @@
+
+
+
+
+
+
diff --git a/code/perception/src/radar_node.py b/code/perception/src/radar_node.py
new file mode 100755
index 00000000..4ddf5b4d
--- /dev/null
+++ b/code/perception/src/radar_node.py
@@ -0,0 +1,114 @@
+#!/usr/bin/env python
+import rospy
+import ros_numpy
+import numpy as np
+from std_msgs.msg import String
+from sensor_msgs.msg import PointCloud2
+from sklearn.cluster import DBSCAN
+import json
+
+
+class RadarNode:
+ """See doc/perception/radar_node.md on how to configure this node."""
+
+ def callback(self, data):
+ """Process radar Point2Cloud data and publish clustered data points.
+
+ Extracts information from radar data
+ and publishes the clustered radar data
+ points as a String message.
+
+ Args:
+ data: Point2Cloud message containing radar data
+ """
+ clustered_points = cluster_radar_data_from_pointcloud(data, 10)
+ clustered_points_json = json.dumps(clustered_points)
+ self.dist_array_radar_publisher.publish(clustered_points_json)
+
+ def listener(self):
+ """Initializes the node and its publishers."""
+ rospy.init_node("radar_node")
+ self.dist_array_radar_publisher = rospy.Publisher(
+ rospy.get_param(
+ "~image_distance_topic", "/paf/hero/Radar/dist_array_unsegmented"
+ ),
+ String,
+ queue_size=10,
+ )
+ rospy.Subscriber(
+ rospy.get_param("~source_topic", "/carla/hero/RADAR"),
+ PointCloud2,
+ self.callback,
+ )
+ rospy.spin()
+
+
+def pointcloud2_to_array(pointcloud_msg):
+ """
+ Converts a ROS PointCloud2 message into a NumPy array and calculates the
+ Euclidean distance of each point from the origin.
+
+ Parameters:
+ - pointcloud_msg: sensor_msgs/PointCloud2
+ The ROS PointCloud2 message containing the 3D points.
+
+ Returns:
+ - np.ndarray
+ A 2D array where each row corresponds to a point in the point cloud:
+ [x, y, z, distance], where "distance" is the distance from the origin.
+ """
+ cloud_array = ros_numpy.point_cloud2.pointcloud2_to_array(pointcloud_msg)
+ distances = np.sqrt(
+ cloud_array["x"] ** 2 + cloud_array["y"] ** 2 + cloud_array["z"] ** 2
+ )
+ return np.column_stack(
+ (cloud_array["x"], cloud_array["y"], cloud_array["z"], distances)
+ )
+
+
+def cluster_radar_data_from_pointcloud(
+ pointcloud_msg, max_distance, eps=1.0, min_samples=2
+):
+ """
+ Filters and clusters points from a ROS PointCloud2 message based on DBSCAN
+ clustering.
+
+ Parameters:
+ - pointcloud_msg: sensor_msgs/PointCloud2
+ The ROS PointCloud2 message containing the 3D points.
+ - max_distance: float
+ Maximum distance to consider points. Points beyond this distance are
+ discarded.
+ - eps: float, optional (default: 1.0)
+ The maximum distance between two points for them to be considered in
+ the same cluster.
+ - min_samples: int, optional (default: 2)
+ The minimum number of points required to form a cluster.
+
+ Returns:
+ - dict
+ A dictionary where the keys are cluster labels (int) and the values
+ are the number of points in each cluster. Returns an empty dictionary
+ if no points are available.
+ """
+ data = pointcloud2_to_array(pointcloud_msg)
+ filtered_data = data[data[:, 3] < max_distance]
+ filtered_data = filtered_data[
+ (filtered_data[:, 1] >= -1)
+ & (filtered_data[:, 1] <= 1)
+ & (filtered_data[:, 2] <= 1.3)
+ & (filtered_data[:, 2] >= -0.7)
+ ]
+ if len(filtered_data) == 0:
+ return {}
+ coordinates = filtered_data[:, :2]
+ clustering = DBSCAN(eps=eps, min_samples=min_samples).fit(coordinates)
+ labels = clustering.labels_
+ clustered_points = {label: list(labels).count(label) for label in set(labels)}
+ clustered_points = {int(label): count for label, count in clustered_points.items()}
+ return clustered_points
+
+
+if __name__ == "__main__":
+ radar_node = RadarNode()
+ radar_node.listener()
diff --git a/code/planning/CMakeLists.txt b/code/planning/CMakeLists.txt
index 34c3ccd0..c6288e03 100755
--- a/code/planning/CMakeLists.txt
+++ b/code/planning/CMakeLists.txt
@@ -13,8 +13,11 @@ project(planning)
find_package(catkin REQUIRED COMPONENTS
perception
rospy
+ rosout
roslaunch
std_msgs
+ geometry_msgs
+ message_generation
)
roslaunch_add_file_check(launch)
@@ -48,9 +51,11 @@ catkin_python_setup()
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
-# add_message_files(
-# MinDistance.msg
-# )
+ add_message_files(
+ FILES
+ NavigationPoint.msg
+ Trajectory.msg
+ )
## Generate services in the 'srv' folder
# add_service_files(
@@ -67,9 +72,12 @@ catkin_python_setup()
# )
## Generate added messages and services with any dependencies listed here
-# generate_messages(
-# perception
-# )
+ generate_messages(
+ DEPENDENCIES
+ std_msgs
+ perception
+ geometry_msgs
+ )
################################################
## Declare ROS dynamic reconfigure parameters ##
@@ -105,7 +113,7 @@ catkin_package(
# LIBRARIES planning
# CATKIN_DEPENDS other_catkin_pkg
# DEPENDS system_lib
- CATKIN_DEPENDS perception rospy
+ CATKIN_DEPENDS perception rospy message_runtime
)
###########
diff --git a/code/planning/msg/NavigationPoint.msg b/code/planning/msg/NavigationPoint.msg
new file mode 100644
index 00000000..e9eb53c9
--- /dev/null
+++ b/code/planning/msg/NavigationPoint.msg
@@ -0,0 +1,3 @@
+geometry_msgs/Point position
+float32 speed
+uint8 behaviour
\ No newline at end of file
diff --git a/code/planning/msg/Trajectory.msg b/code/planning/msg/Trajectory.msg
new file mode 100644
index 00000000..94060cdd
--- /dev/null
+++ b/code/planning/msg/Trajectory.msg
@@ -0,0 +1,2 @@
+Header header
+planning/NavigationPoint[] navigationPoints
\ No newline at end of file
diff --git a/code/planning/package.xml b/code/planning/package.xml
index a321a109..daf36bc6 100755
--- a/code/planning/package.xml
+++ b/code/planning/package.xml
@@ -47,6 +47,9 @@
+ message_generation
+ message_runtime
+
rospy
roslaunch
@@ -57,6 +60,7 @@
carla_msgs
sensor_msgs
std_msgs
+ geometry_msgs
perception
perception
diff --git a/code/planning/src/BehaviourEnum.py b/code/planning/src/BehaviourEnum.py
new file mode 100644
index 00000000..361b0b43
--- /dev/null
+++ b/code/planning/src/BehaviourEnum.py
@@ -0,0 +1,8 @@
+from enum import IntEnum
+
+# getattr(Behaviour, "name").value returns the ID
+# Behaviour(id) returns Behaviour.NAME
+
+
+class BehaviourEnum(IntEnum):
+ CRUISING = 0
diff --git a/doc/acting/README.md b/doc/acting/README.md
index f55e66eb..e9845154 100644
--- a/doc/acting/README.md
+++ b/doc/acting/README.md
@@ -2,9 +2,7 @@
This folder contains the documentation of the acting component.
-1. [Architecture](./architecture_documentation.md)
-2. [Overview of the Velocity Controller](./velocity_controller.md)
-3. [Overview of the Steering Controllers](./steering_controllers.md)
-4. [Overview of the Vehicle Controller Component](./vehicle_controller.md)
-5. [How to test/tune acting components independedly](./acting_testing.md)
-6. [Main frame publisher](./mainframe_publisher.md)
+1. [Overview and Architecture](./architecture_documentation.md)
+2. [Passthrough](./passthrough.md)
+3. [Main frame publisher](./main_frame_publisher.md)
+4. [How to test/tune the acting component](./acting_testing.md)
diff --git a/doc/acting/acting_testing.md b/doc/acting/acting_testing.md
index 49bd88e7..108e3c3a 100644
--- a/doc/acting/acting_testing.md
+++ b/doc/acting/acting_testing.md
@@ -8,15 +8,15 @@
## Acting_Debug_Node
-The [Acting_Debug_Node](../../code/acting/src/acting/Acting_Debug_Node.py) allows you to tune/test/verify all acting components independently of Planning-Inputs and also lets you easily output the data needed to plot/verify the tuning/testing you have done.
+The [Acting_Debug_Node](../../code/acting/src/acting/Acting_Debug_Node.py) allows you to tune/test/verify all acting and control components independently of Planning-Inputs and also lets you easily output the data needed to plot/verify the tuning/testing you have done.
There is a dedicated [acting_debug.launch](../../code/acting/launch/acting_debug.launch) file which starts the acting component **as well as the necesarry perception components** automatically. It is recommended to first test the [Acting_Debug_Node](../../code/acting/src/acting/Acting_Debug_Node.py)
with an empty road scenario. The following guide provides instructions on how to launch this setup.
### Setup for Testing with the Debug-Node
-To use the [Acting_Debug_Node](../../code/acting/src/acting/Acting_Debug_Node.py) you first have to edit a few files in your current branch: \\
-**! Make sure to revert these changes when pushing your branch!**
+To use the [Acting_Debug_Node](../../code/acting/src/acting/Acting_Debug_Node.py) you first have to edit a few files in your current branch:
+>[!WARNING]! Make sure to revert these changes when pushing your branch!
- In [dev.launch](../../code/agent/launch/dev.launch) the [agent.launch](../../code/agent/launch/agent.launch) file is included. Change this to include [acting_debug.launch](../../code/acting/launch/acting_debug.launch) from the **acting** package.
As mentioned above this includes everything we need.
diff --git a/doc/acting/architecture_documentation.md b/doc/acting/architecture_documentation.md
index 5c1aeb9d..4bb6f520 100644
--- a/doc/acting/architecture_documentation.md
+++ b/doc/acting/architecture_documentation.md
@@ -1,68 +1,46 @@
-# Architecture
+# Acting: Overview and Architecture
-**Summary**: This documentation shows the current Acting Architecture.
+**Summary**: The acting component receives information from the [planning component](./../planning/README.md) as well
+as the [perception component](./../perception/README.md). It processes this information in order to
+navigate on a local basis. This information is then processed in the [control_component](./../control/README.md).
-- [Architecture](#architecture)
- - [Acting Architecture](#acting-architecture)
- - [Summary of Acting Components](#summary-of-acting-components)
- - [pure\_pursuit\_controller.py](#pure_pursuit_controllerpy)
- - [stanley\_controller.py](#stanley_controllerpy)
- - [velocity\_controller.py](#velocity_controllerpy)
- - [vehicle\_controller.py](#vehicle_controllerpy)
- - [helper\_functions.py](#helper_functionspy)
- - [MainFramePublisher.py](#mainframepublisherpy)
+- [Acting Architecture](#acting-architecture)
+- [Components of acting](#components-of-acting)
+ - [passthrough.py](#passthroughpy)
+ - [main\_frame\_publisher.py](#main_frame_publisherpy)
+ - [helper\_functions.py](#helper_functionspy)
## Acting Architecture
-![MISSING: Acting-ARCHITECTURE](../assets/acting/Architecture_Acting.png)
+![MISSING: Acting-ARCHITECTURE](./../assets/acting/acting_architecture.png)
-## Summary of Acting Components
+> [!NOTE]
+> [Click here to go to control architecture](./../control/architecture_documentation.md)
-### pure_pursuit_controller.py
+## Components of acting
-- Inputs:
- - **trajectory**: Path
- - **current_pos**: PoseStamped
- - **Speed**: CarlaSpeedometer
- - **current_heading**: Float32
-- Outputs:
- - **pure_pursuit_steer**: Float32
- - **pure_p_debug**: Debug
+### passthrough.py
-### stanley_controller.py
+> [!TIP]
+> For documentation on passthrough component see: [passthrough](./passthrough.md)
-- Inputs:
- - **trajectory**: Path
- - **current_pos**: PoseStamped
- - **Speed**: CarlaSpeedometer
- - **current_heading**: Float32
-- Outputs:
- - **stanley_steer**: Float32
- - **stanley_debug**: StanleyDebug
+### main_frame_publisher.py
-### velocity_controller.py
+> [!TIP]
+> Follow this link for [Documentation](./main_frame_publisher.md) on this Node.
- Inputs:
- - **target_velocity**: Float32
- - **Speed**: CarlaSpeedometer
-- Outputs:
- - **throttle**: Float32
- - **brake**: Float32
-
-### vehicle_controller.py
-
-- Inputs:
- - **emergency**: Bool
- - **curr_behavior**: String
- - **Speed**: CarlaSpeedometer
- - **throttle**: Float32
- - **brake**: Float32
- - **pure_pursuit_steer**: Float32
- - **stanley_steer**: Float32
+ - **current_pos**: PoseStampled
+ - **current_heading**: Float32
- Outputs:
- - **vehicle_control_cmd**: [CarlaEgoVehicleControl](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg)
- - **status**: Bool
- - **emergency**: Bool
+ - **transform**: broadcasts heroframe-transform via TransformBroadcaster
+- This node handles the translation from the static main frame to the moving hero frame. The hero frame always moves and rotates as the ego vehicle does. The hero frame is used by sensors like the lidar. Rviz also uses the hero frame. The main frame is used for planning
+- rotation = - **current_heading**
+- position x = cos(rotation) \* **current_pos**.x + sin(rotation) \* **current_pos**.y
+- position y = sin(rotation) \* **current_pos**.x + cos(rotation) \* **current_pos**.y
+- position z = - **current_pos**.z
+- rot_quat = rot as quaternion
+- **transform** = position x/y/z, rot_quat, Timestamp(now), “global”, “hero”
### helper_functions.py
@@ -96,18 +74,3 @@ Interpolate linearly between start and end, with a minimal distance of interval_
Remove duplicates in the given List of tuples, if the distance between them is less than min_dist.
- **interpolate_route(orig_route: List[Tuple[float, float]], interval_m=0.5)**:\
Interpolate the given route with points inbetween,holding the specified distance interval threshold.
-
-### MainFramePublisher.py
-
-- Inputs:
- - **current_pos**: PoseStampled
- - **current_heading**: Float32
-- Outputs:
- - **transform**: broadcasts heroframe-transform via TransformBroadcaster
-- This node handles the translation from the static main frame to the moving hero frame. The hero frame always moves and rotates as the ego vehicle does. The hero frame is used by sensors like the lidar. Rviz also uses the hero frame. The main frame is used for planning
-- rotation = - **current_heading**
-- position x = cos(rotation) \* **current_pos**.x + sin(rotation) \* **current_pos**.y
-- position y = sin(rotation) \* **current_pos**.x + cos(rotation) \* **current_pos**.y
-- position z = - **current_pos**.z
-- rot_quat = rot as quaternion
-- **transform** = position x/y/z, rot_quat, Timestamp(now), “global”, “hero”
diff --git a/doc/acting/passthrough.md b/doc/acting/passthrough.md
new file mode 100644
index 00000000..eabd32b1
--- /dev/null
+++ b/doc/acting/passthrough.md
@@ -0,0 +1,25 @@
+# Passthrough
+
+>[!NOTE]
+>The passthrough component is a temporary solution while beeing in the transitioning phase of
+>splitting up the acting component into acting and control.
+
+**Summary:** This page is ought to provide an overview of the passthrough node and
+reason why it exists
+
+- [Overview](#overview)
+- [Reasoning](#reasoning)
+
+## Overview
+
+The passthrough node subscribes to topics on a global scale and republishes them into the "paf/acting" namespace. The control package subscribes to these re-emitted topics.
+
+> [!NOTE]
+> See [acting architecture](./architecture_documentation.md) for further information.
+
+## Reasoning
+
+Before the control package was outsourced and became its own package it resided within the acting package.
+Therefor many global dependencies existed in the control package. As the goal of the outsourcing was
+to eliminate global dependencies in control theory the passthrough node was created as a first stepping
+stone towards independence.
diff --git a/doc/assets/acting/acting_architecture.png b/doc/assets/acting/acting_architecture.png
new file mode 100644
index 00000000..fd2a780d
Binary files /dev/null and b/doc/assets/acting/acting_architecture.png differ
diff --git a/doc/assets/acting/Architecture_Acting.png b/doc/assets/acting/architecture_acting_legacy.png
similarity index 100%
rename from doc/assets/acting/Architecture_Acting.png
rename to doc/assets/acting/architecture_acting_legacy.png
diff --git a/doc/assets/acting/Steering_PurePursuit.png b/doc/assets/control/Steering_PurePursuit.png
similarity index 100%
rename from doc/assets/acting/Steering_PurePursuit.png
rename to doc/assets/control/Steering_PurePursuit.png
diff --git a/doc/assets/acting/Steering_PurePursuit_Tuning.png b/doc/assets/control/Steering_PurePursuit_Tuning.png
similarity index 100%
rename from doc/assets/acting/Steering_PurePursuit_Tuning.png
rename to doc/assets/control/Steering_PurePursuit_Tuning.png
diff --git a/doc/assets/acting/Steering_Stanley.png b/doc/assets/control/Steering_Stanley.png
similarity index 100%
rename from doc/assets/acting/Steering_Stanley.png
rename to doc/assets/control/Steering_Stanley.png
diff --git a/doc/assets/acting/Steering_Stanley_ComparedToPurePur.png b/doc/assets/control/Steering_Stanley_ComparedToPurePur.png
similarity index 100%
rename from doc/assets/acting/Steering_Stanley_ComparedToPurePur.png
rename to doc/assets/control/Steering_Stanley_ComparedToPurePur.png
diff --git a/doc/assets/acting/VelContr_PID_BrakingWithThrottlePID.png b/doc/assets/control/VelContr_PID_BrakingWithThrottlePID.png
similarity index 100%
rename from doc/assets/acting/VelContr_PID_BrakingWithThrottlePID.png
rename to doc/assets/control/VelContr_PID_BrakingWithThrottlePID.png
diff --git a/doc/assets/acting/VelContr_PID_StepResponse.png b/doc/assets/control/VelContr_PID_StepResponse.png
similarity index 100%
rename from doc/assets/acting/VelContr_PID_StepResponse.png
rename to doc/assets/control/VelContr_PID_StepResponse.png
diff --git a/doc/assets/acting/VelContr_PID_differentVelocities.png b/doc/assets/control/VelContr_PID_differentVelocities.png
similarity index 100%
rename from doc/assets/acting/VelContr_PID_differentVelocities.png
rename to doc/assets/control/VelContr_PID_differentVelocities.png
diff --git a/doc/assets/control/control_architecture.png b/doc/assets/control/control_architecture.png
new file mode 100644
index 00000000..b9c1f6da
Binary files /dev/null and b/doc/assets/control/control_architecture.png differ
diff --git a/doc/assets/acting/emergency_brake_stats_graph.png b/doc/assets/control/emergency_brake_stats_graph.png
similarity index 100%
rename from doc/assets/acting/emergency_brake_stats_graph.png
rename to doc/assets/control/emergency_brake_stats_graph.png
diff --git a/doc/assets/overview.jpg b/doc/assets/overview.jpg
index 3bdc9225..7c6b3c76 100644
Binary files a/doc/assets/overview.jpg and b/doc/assets/overview.jpg differ
diff --git a/doc/control/README.md b/doc/control/README.md
new file mode 100644
index 00000000..211d7149
--- /dev/null
+++ b/doc/control/README.md
@@ -0,0 +1,8 @@
+# Documentation of control component
+
+This folder contains the documentation of the control component.
+
+1. [Overview and Architecture](./architecture_documentation.md)
+2. [Overview of the Velocity Controller](./velocity_controller.md)
+3. [Overview of the Steering Controllers](./steering_controllers.md)
+4. [Overview of the Vehicle Controller Component](./vehicle_controller.md)
diff --git a/doc/control/architecture_documentation.md b/doc/control/architecture_documentation.md
new file mode 100644
index 00000000..89c44042
--- /dev/null
+++ b/doc/control/architecture_documentation.md
@@ -0,0 +1,84 @@
+# Control: Overview and Architecture
+
+**Summary**:
+The control component applies control theory based on a local trajectory provided
+by the [acting component](./../acting/README.md). It uses knowledge of the current state
+of the vehicle in order to send [CarlaEgoVehicleControl](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg) commands to the Simulator. This component also sends the [/carla/hero/status](https://leaderboard.carla.org/get_started/) command,
+which starts the simulation.
+
+- [Control Architecture](#control-architecture)
+- [Summary of Control Components](#summary-of-control-components)
+ - [Steering controllers](#steering-controllers)
+ - [pure\_pursuit\_controller.py](#pure_pursuit_controllerpy)
+ - [stanley\_controller.py](#stanley_controllerpy)
+ - [Velocity controllers](#velocity-controllers)
+ - [velocity\_controller.py](#velocity_controllerpy)
+ - [vehicle\_controller.py](#vehicle_controllerpy)
+
+## Control Architecture
+
+![MISSING: Control-ARCHITECTURE](./../assets/control/control_architecture.png)
+
+> [!NOTE]
+> [Click here to go to acting architecture](./../acting/architecture_documentation.md)
+
+## Summary of Control Components
+
+### Steering controllers
+
+> [!TIP]
+> Follow this link for the [Documentation](./steering_controllers.md) on steering controllers.
+
+#### pure_pursuit_controller.py
+
+- Inputs:
+ - **trajectory**: Path
+ - **current_pos**: PoseStamped
+ - **Speed**: CarlaSpeedometer
+ - **current_heading**: Float32
+- Outputs:
+ - **pure_pursuit_steer**: Float32
+ - **pure_p_debug**: Debug
+
+#### stanley_controller.py
+
+- Inputs:
+ - **trajectory**: Path
+ - **current_pos**: PoseStamped
+ - **Speed**: CarlaSpeedometer
+ - **current_heading**: Float32
+- Outputs:
+ - **stanley_steer**: Float32
+ - **stanley_debug**: StanleyDebug
+
+### Velocity controllers
+
+> [!TIP]
+> Follow this link for the [Documentation](./velocity_controller.md) on velocity component.
+
+#### velocity_controller.py
+
+- Inputs:
+ - **target_velocity**: Float32
+ - **Speed**: CarlaSpeedometer
+- Outputs:
+ - **throttle**: Float32
+ - **brake**: Float32
+
+### vehicle_controller.py
+
+> [!TIP]
+> Follow this link for [Documentation](./vehicle_controller.md) on vehicle controller.
+
+- Inputs:
+ - **emergency**: Bool
+ - **curr_behavior**: String
+ - **Speed**: CarlaSpeedometer
+ - **throttle**: Float32
+ - **brake**: Float32
+ - **pure_pursuit_steer**: Float32
+ - **stanley_steer**: Float32
+- Outputs:
+ - **vehicle_control_cmd**: [CarlaEgoVehicleControl](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg)
+ - **status**: Bool
+ - **emergency**: Bool
diff --git a/doc/acting/steering_controllers.md b/doc/control/steering_controllers.md
similarity index 79%
rename from doc/acting/steering_controllers.md
rename to doc/control/steering_controllers.md
index e7c0a474..3b8cacdb 100644
--- a/doc/acting/steering_controllers.md
+++ b/doc/control/steering_controllers.md
@@ -2,10 +2,9 @@
**Summary:** This page provides an overview of the current status of both steering controllers, the PurePursuit and the Stanley Controller.
-- [Overview of the Steering Controllers](#overview-of-the-steering-controllers)
- - [General Introduction to Steering Controllers](#general-introduction-to-steering-controllers)
- - [PurePursuit Controller](#purepursuit-controller)
- - [Stanley Controller](#stanley-controller)
+- [General Introduction to Steering Controllers](#general-introduction-to-steering-controllers)
+- [PurePursuit Controller](#purepursuit-controller)
+- [Stanley Controller](#stanley-controller)
## General Introduction to Steering Controllers
@@ -16,12 +15,12 @@ Currently, two different, independently running Steering Controllers are impleme
## PurePursuit Controller
-The [PurePursuit Controller's](../../code/acting/src/acting/pure_pursuit_controller.py) main feature to determine a steering-output is the so-called **look-ahead-distance d_la** (l_d in Image).
+The [PurePursuit Controller's](../../code/control/src/pure_pursuit_controller.py) main feature to determine a steering-output is the so-called **look-ahead-distance d_la** (l_d in Image).
For more indepth information about the PurePursuit Controller, click [this link](https://de.mathworks.com/help/nav/ug/pure-pursuit-controller.html) and [this link](https://thomasfermi.github.io/Algorithms-for-Automated-Driving/Control/PurePursuit.html).
At every moment it checks a point of the trajectory in front of the vehicle with a distance of **$d_{la}$** and determines a steering-angle so that the vehicle will aim straight to this point of the trajectory.
-![MISSING: PurePursuit-ShowImage](../assets/acting/Steering_PurePursuit.png)
+![MISSING: PurePursuit-ShowImage](../assets/control/Steering_PurePursuit.png)
This **look-ahead-distance $d_{la}$** is velocity-dependent, as at higher velocities, the controller should look further ahead onto the trajectory.
@@ -32,17 +31,17 @@ $$ \delta = arctan({2 \cdot L_{vehicle} \cdot sin(\alpha) \over d_{la}})$$
To tune the PurePursuit Controller, you can tune the factor of this velocity-dependence **$k_{ld}$**.
Also, for an unknown reason, we needed to add an amplification to the output-steering signal before publishing aswell **$k_{pub}$**, which highly optimized the steering performance in the dev-launch:
-![MISSING: PurePursuit-Optimization_Image](../assets/acting/Steering_PurePursuit_Tuning.png)
+![MISSING: PurePursuit-Optimization_Image](../assets/control/Steering_PurePursuit_Tuning.png)
**NOTE:** The **look-ahead-distance $d_{la}$** should be highly optimally tuned already for optimal sensor data and on the dev-launch!
In the Leaderboard-Launch this sadly does not work the same, so it requires different tuning and needs to be optimized/fixed.
## Stanley Controller
-The [Stanley Controller's](../../code/acting/src/acting/stanley.py) main features to determine a steering-output is the so-called **cross-track-error** (e_fa in Image) and the **trajectory-heading** (theta_e in Image).
+The [Stanley Controller's](../../code/control/src/stanley_controller.py ) main features to determine a steering-output is the so-called **cross-track-error** (e_fa in Image) and the **trajectory-heading** (theta_e in Image).
For more indepth information about the Stanley Controller, click [this link](https://medium.com/roboquest/understanding-geometric-path-tracking-algorithms-stanley-controller-25da17bcc219) and [this link](https://ai.stanford.edu/~gabeh/papers/hoffmann_stanley_control07.pdf).
-![MISSING: Stanley-SHOW-IMAGE](../assets/acting/Steering_Stanley.png)
+![MISSING: Stanley-SHOW-IMAGE](../assets/control/Steering_Stanley.png)
At every moment it checks the closest point of the trajectory to itself and determines a two steering-angles:
@@ -55,7 +54,7 @@ $$ \delta = \theta_e - arctan({k_{ce} \cdot e_{fa} \over v})$$
To tune the Stanley Controller, you tune the factor **$k_{ce}$**, which amplifies (or diminishes) how strong the **cross-track-error**-calculated steering-angle will "flow" into the output steering-angle.
-![MISSING: Stanley-Compared to PurePursuit](../assets/acting/Steering_Stanley_ComparedToPurePur.png)
+![MISSING: Stanley-Compared to PurePursuit](../assets/control/Steering_Stanley_ComparedToPurePur.png)
As for the PurePursuit Controller, sadly the achieved good tuning in the Dev-Launch was by far too strong for the Leaderboard-Launch, which is why we needed to Hotfix the Steering in the last week to Tune Stanley alot "weaker". We do not exactly know, why the two launches are this different.
(Dev-Launch and Leaderboard-Launch differentiate in synchronicity, Dev-Launch is synchronous, Leaderboard-Launch is asynchronous?)
diff --git a/doc/acting/vehicle_controller.md b/doc/control/vehicle_controller.md
similarity index 81%
rename from doc/acting/vehicle_controller.md
rename to doc/control/vehicle_controller.md
index 62dfefe7..9a307c02 100644
--- a/doc/acting/vehicle_controller.md
+++ b/doc/control/vehicle_controller.md
@@ -2,15 +2,14 @@
**Summary:** This page provides an overview of the current status of the Vehicle Controller Component.
-- [Overview of the Vehicle Controller Component](#overview-of-the-vehicle-controller-component)
- - [General Introduction to the Vehicle Controller Component](#general-introduction-to-the-vehicle-controller-component)
- - [Vehicle Controller Output](#vehicle-controller-output)
- - [Emergency Brake](#emergency-brake)
- - [Unstuck Routine](#unstuck-routine)
+- [General Introduction to the Vehicle Controller Component](#general-introduction-to-the-vehicle-controller-component)
+- [Vehicle Controller Output](#vehicle-controller-output)
+- [Emergency Brake](#emergency-brake)
+- [Unstuck Routine](#unstuck-routine)
## General Introduction to the Vehicle Controller Component
-The [Vehicle Controller](../../code/acting/src/acting/vehicle_controller.py) collects all information from the other controllers in Acting ```throttle```, ```brake```, ```pure_puresuit_steer``` and ```stanley_steer```
+The [Vehicle Controller](../../code/control/src/vehicle_controller.py) collects all information from the other controllers in Control ```throttle```, ```brake```, ```pure_puresuit_steer``` and ```stanley_steer```
to fill them into the CARLA-Vehicle Command Message ```vehicle_control_cmd``` and send this to the CARLA simulator.
It also reacts to some special case - Messages from Planning, such as emergency-braking or executing the unstuck-routine.
@@ -50,7 +49,7 @@ This is done to prevent firing the emergency brake each time the main loop is re
Comparison between normal braking and emergency braking:
-![Braking Comparison](/doc/assets/acting/emergency_brake_stats_graph.png)
+![Braking Comparison](/doc/assets/control/emergency_brake_stats_graph.png)
_Please be aware, that this bug abuse might not work in newer updates!_
@@ -65,5 +64,5 @@ Inside the Unstuck Behavior we want drive backwards without steering, which is w
It's also important to note, that we always receive a target_speed of -3 when in the unstuck routine. Also the __reverse attribute is True in this case.
This is the only case we can drive backwards for now. When implementing an exhausting backwards driving approach this has to be kept in mind, because we DO NOT try to drive at the speed of -3 m/s. We only use the -3 as a keyword for driving backwards at full throttle for a specefic amount of time!
-(see [velocity_controller.py](/code/acting/src/acting/velocity_controller.py)
+(see [velocity_controller.py](/code/control/src/velocity_controller.py)
and [maneuvers.py](/code/planning/src/behavior_agent/behaviours/maneuvers.py))
diff --git a/doc/acting/velocity_controller.md b/doc/control/velocity_controller.md
similarity index 76%
rename from doc/acting/velocity_controller.md
rename to doc/control/velocity_controller.md
index b4715997..6315e2bb 100644
--- a/doc/acting/velocity_controller.md
+++ b/doc/control/velocity_controller.md
@@ -2,13 +2,12 @@
**Summary:** This page provides an overview of the current status of the velocity_controller.
-- [Overview of the Velocity Controller](#overview-of-the-velocity-controller)
- - [General Introduction to Velocity Controller](#general-introduction-to-velocity-controller)
- - [Current Implementation](#current-implementation)
+- [General Introduction to Velocity Controller](#general-introduction-to-velocity-controller)
+- [Current Implementation](#current-implementation)
## General Introduction to Velocity Controller
-The [velocity_controller](../../code/acting/src/acting/velocity_controller.py) implements our way to make the CARLA-Vehicle drive at a ```target_velocity``` (published by Planning) by using a tuned PID-Controller to calculate a ```throttle``` and a ```brake``` for the CARLA-Vehicle-Command.
+The [velocity_controller](../../code/control/src/velocity_controller.py) implements our way to make the CARLA-Vehicle drive at a ```target_velocity``` (published by Planning) by using a tuned PID-Controller to calculate a ```throttle``` and a ```brake``` for the CARLA-Vehicle-Command.
For more information about PID-Controllers and how they work, follow [this link](https://en.wikipedia.org/wiki/Proportional%E2%80%93integral%E2%80%93derivative_controller).
**IMPORTANT:** The CARLA ```vehicle_control_cmd``` only allows you to use a ```throttle``` and a ```brake``` value, both with an allowed range from 0-1, to control the driven speed.
@@ -17,16 +16,16 @@ For more information about PID-Controllers and how they work, follow [this link]
Currently, we use a tuned PID-Controller which was tuned for the speed of 14 m/s (around 50 km/h), as this is the most commonly driven velocity in this simulation:
-![MISSING: PID-TUNING-IMAGE](../assets/acting/VelContr_PID_StepResponse.png)
+![MISSING: PID-TUNING-IMAGE](../assets/control/VelContr_PID_StepResponse.png)
Be aware, that the CARLA-Vehicle shifts gears automatically, resulting in the bumps you see!
As PID-Controllers are linear by nature, the velocity-system is therefore linearized around 50 km/h, meaning the further you deviate from 50 km/h the worse the controller's performance gets:
-![MISSING: PID-LINEARIZATION-IMAGE](../assets/acting/VelContr_PID_differentVelocities.png)
+![MISSING: PID-LINEARIZATION-IMAGE](../assets/control/VelContr_PID_differentVelocities.png)
As the Velocity Controller also has to handle braking, we currently use ```throttle```-optimized PID-Controller to calculate ```brake``` aswell (Since adding another Controller, like a P-Controller, did not work nearly as well!):
-![MISSING: PID-BRAKING-IMAGE](../assets/acting/VelContr_PID_BrakingWithThrottlePID.png)
+![MISSING: PID-BRAKING-IMAGE](../assets/control/VelContr_PID_BrakingWithThrottlePID.png)
Currently, there is no general backwards-driving implemented here, as this was not needed (other than the [Unstuck Routine](/doc/planning/Behavior_detailed.md)).
diff --git a/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md b/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md
index 0c41eeef..603190f1 100644
--- a/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md
+++ b/doc/dev_talks/paf24/sprint_review_meeting_guidelines.md
@@ -43,7 +43,8 @@
- Example: A team of three has a total of 15 minutes and may allocate time as they see fit.
- A unified grade will be given unless individual assessment is warranted.
- Timeboxing will be strictly enforced: only content shared within the allotted time will be evaluated. Presentations will be stopped at the time limit.
-- TODO The sprint review presentation guideline will be updated.
+- The sprint review presentation guideline was updated in [#452](https://github.com/una-auxme/paf/issues/452).
+ - The [sprint_review_presentation.md](../../development/sprint_review_presentation.md) is updated.
## 3. Sprint Review Schedule
diff --git a/doc/development/project_management.md b/doc/development/project_management.md
index 29a1a0f0..ef5e45d7 100644
--- a/doc/development/project_management.md
+++ b/doc/development/project_management.md
@@ -13,6 +13,28 @@ Issues can be added via the [issues overview](https://github.com/una-auxme/paf/i
By clicking "New issue" in the overview you have different templates to create the issue.
+After creating the issue it has to be added to the project board. The project board is used to keep track of the
+progress of the issue. The project board can be found [here](https://github.com/orgs/una-auxme/projects/3).
+
+For tracking time and complexity of the issue we will use the predefined `Priority` and `Size` states of the PAF Project
+Backlog Board.
+
+Priority has following states:
+
+- `Urgent`: Critical bug causing system crash, needs immediate fix.
+- `High`: Major feature request or significant bug affecting many users.
+- `Medium`: Minor feature request or bug with a workaround.
+- `Low`: Cosmetic changes or minor improvements.
+
+Size has following states:
+
+- `Tiny`: Small typo fix or minor code refactor. Estimated time: 30 minutes.
+- `Small`: Simple bug fix or small feature addition. Estimated time: 1-2 hours.
+- `Medium`: Moderate feature addition or multiple bug fixes. Estimated time: 1-2 days.
+- `Large`: Major feature implementation or significant refactor. Estimated time: 1-2 weeks.
+- `X-Large`: Large-scale feature or complete module overhaul. Estimated time: 2-4 weeks. Especially `EPIC` issues should
+ be tagged with this size.
+
## 2. Create a Pull Request
To create a pull request, go to the [branches overview](https://github.com/una-auxme/paf/branches) and select ``New Pull Request`` for the branch you want to create a PR for.
diff --git a/doc/development/sprint_review_presentation.md b/doc/development/sprint_review_presentation.md
index 0452d84e..b875ff5c 100644
--- a/doc/development/sprint_review_presentation.md
+++ b/doc/development/sprint_review_presentation.md
@@ -1,76 +1,51 @@
# Sprint Review Presentation
-**Summary:** Guidelines for creating effective presentations for Sprint Reviews in the PAF project.
+**Summary:** Guidelines for creating effective presentations for the Sprint Reviews in the PAF project.
-- [1. General Sprint Progress Overview Presentation](#1-general-sprint-progress-overview-presentation)
-- [2. Individual Pull Request (PR) Presentations](#2-individual-pull-request-pr-presentations)
-- [3. Presentation Style](#3-presentation-style)
+- [1. Group Presentations](#1-group-presentations)
+- [2. Presentation Style](#2-presentation-style)
Creating a good presentation for a **Sprint Review** in PAF is important for communicating the team's achievements, identifying challenges, and planning for future work.
-To present the sprint progress effectively, especially when dealing with complex software projects, it can be beneficial to split the presentations into two distinct parts:
+## 1. Group Presentations
-1. **General Sprint Progress Overview**: This focuses on the big-picture updates, team-wide accomplishments, challenges, and next steps.
-2. **Individual Pull Request (PR) Presentations**: These dive into the details of specific features or changes made during the sprint.
+These are technical presentations meant to present project progress from the sprint.
+Not every PR has to be presented, but **each students contribution should be presented**.
-## 1. General Sprint Progress Overview Presentation
+**Structure of Presentation**:
-This presentation is designed for a broader audience and focuses on the overall progress made during the sprint. It highlights major milestones, project status, and challenges, without diving into technical implementation details.
-There should be one general overview presentation per sprint, typically delivered a new student who has not presented the general overview before.
-
-**Structure of the General Overview**:
-
-- **Title Slide**: Sprint number, project name, team, and sprint dates.
-- **Agenda**: Outline the structure of the presentation.
- - *See below*
-- **Sprint Goals**: Briefly describe the objectives of the sprint and how they fit into the overall project roadmap.
-- **Completed Work**: Provide an overview of features that were completed. This section should focus on **overall vehicle improvement** rather than technical details.
- - Optionally include a **demo** of key features.
- - **Before-and-after visuals** of new functionality if applicable.
-- **In-progress Work**: Mention features or tasks that were started but not completed, along with explanations of why they weren’t finished.
-- **Challenges & Blockers**: Present the key blockers and how they were addressed or escalated. If some remain unresolved, suggest plans for mitigation.
-- **Sprint Metrics**: Include relevant metrics:
- - Any improvements in testing or driving score.
-- **Next Steps**: Outline the focus areas for the next sprint, upcoming deadlines, and potential risks.
-
-**Duration**: 5-20 minutes, depending on the complexity of the sprint.
-
-## 2. Individual Pull Request (PR) Presentations
-
-These are more focused, technical presentations meant to review individual pull requests (PRs) from the sprint. They are aimed at the development team and technical stakeholders, providing detailed insight into the code changes, implementation logic, and technical considerations of each PR.
-Not every PR has to be presented, but **every student should be able to highlight their contributions**.
-
-**Structure of the PR Presentation**:
-
-- **Title Slide**: Pull request title, associated issue number(s), and contributor(s).
+- **Title Slide**: Area of contribution, PR numbers, and contributor(s).
- **Agenda**:
- - *See below*
-- **PR Overview**: Start with the problem or issue the PR addresses.
- - Describe the goal of the changes (e.g., adding a feature, fixing a bug, refactoring code).
-- **Key Accomplishments**: Go over the technical changes made in the PR.
- - **Code snippets**: Highlight important parts of the code that were changed or added.
- - **Design patterns or architectural choices**: Explain any significant technical decisions.
-- **Technical Challenges and Solutions**: Discuss any technical difficulties encountered while implementing the PR.
- - Mention how challenges were overcome and what alternatives were considered.
-- **Code Review Outcomes**: Summarize any feedback from peer reviews.
- - Highlight any requested changes and how they were addressed.
- - Point out best practices followed or any areas for future improvement.
-- **Testing and Validation**: Show how the changes were tested.
+ - Clearly outline what will be covered.
+- **Overview**:
+ - Start by describing the problem or feature request being addressed.
+ - Explain the goal of the changes.
+- **Key Accomplishments**:
+ - Summarize the technical changes made during the sprint.
+ - Highlight key features implemented or problems solved.
+ - Design Patterns/Architectural Choices: Explain significant technical decisions.
+- **Technical Challenges and Solutions**:
+ - Discuss challenges encountered and how they were resolved.
+ - Outline alternative approaches considered, if any.
+- **Code Review Outcomes**:
+ - Summarize feedback received during peer reviews.
+ - Highlight requested changes and how they were addressed.
+ - Mention best practices followed and areas for improvement.
+- **Testing and Validation**: Explain how the changes were tested.
- **Automated tests**: Unit, integration, or end-to-end tests that were added or updated.
- **Manual tests**: If manual validation was done, explain the scenarios tested.
-- **Demo (if applicable)**: Provide a quick live demo or walkthrough of the feature or bug fix that the PR addresses.
-- **Next Steps**: If the PR impacts other work or needs further iterations, describe those next steps.
+- **Demo**: Provide a quick demo or walkthrough of the feature or bug fix that the PR addresses.
+ - Prepare screenshots or recordings.
+- **Next Steps**: If the changes impacts other work or needs further iterations, describe those next steps.
-**Duration**: 5-10 minutes per Pull-Request.
+**Duration**: **5 minutes** per person.
-## 3. Presentation Style
+## 2. Presentation Style
- **Focus on outcomes**: Highlight the progress made and how it impacts the overall project goals.
- **Use visuals and charts**: Use screenshots, graphs, and videos to illustrate progress.
-- **Interactive**: Ask for feedback, highlight areas that require input or decisions.
- **Keep it high-level**: Avoid too much technical jargon.
- **Stay concise**: Respect everyone’s time and keep the presentation focused on what matters most.
-- **Collaborate**: Collaborate with the team to ensure all aspects of the sprint are covered.
- **Consistent Slide Design**: Use a consistent slide design (fonts, colors, layout) to improve readability.
- Templates for AuxMe-Presentations:
diff --git a/doc/general/README.md b/doc/general/README.md
index cbf937f4..fbde8778 100644
--- a/doc/general/README.md
+++ b/doc/general/README.md
@@ -4,4 +4,5 @@ This Folder contains instruction on installation, execution and architecture of
1. [Installation](./installation.md)
2. [Execution](./execution.md)
-3. [Current architecture of the agent](./architecture.md)
+3. [Current architecture of the agent](./architecture_current.md)
+4. [Planned architecture of the agent](./architecture_planned.md)
diff --git a/doc/general/architecture_current.md b/doc/general/architecture_current.md
new file mode 100644
index 00000000..aa0a472a
--- /dev/null
+++ b/doc/general/architecture_current.md
@@ -0,0 +1,371 @@
+# Current architecture of the vehicle agent
+
+**Summary:** This page gives an overview over the current general architecture of the vehicle agent.
+The document contains an overview over all [nodes](#overview) and [topics](#topics). Additionally a visual thematic grouping of the subsystems of the agent is done for an easier optical identification which nodes and topics belong/contribute to them.
+
+- [Overview](#overview)
+- [Perception](#perception)
+ - [Vision Node (vision\_node.py)](#vision-node-vision_nodepy)
+ - [Traffic Light Detection (traffic\_light\_node.py)](#traffic-light-detection-traffic_light_nodepy)
+ - [Position Heading Node (position\_heading\_publisher\_node.py)](#position-heading-node-position_heading_publisher_nodepy)
+ - [Global distances (global\_plan\_distance\_publisher.py)](#global-distances-global_plan_distance_publisherpy)
+ - [Kalman filtering (kalman\_filter.py)](#kalman-filtering-kalman_filterpy)
+ - [Localization](#localization)
+- [Planning](#planning)
+ - [PrePlaner (global\_planner.py)](#preplaner-global_plannerpy)
+ - [Behavior Agent (behavior\_agent)](#behavior-agent-behavior_agent)
+ - [Local Planning](#local-planning)
+- [Acting](#acting)
+ - [MainFramePublisher](#mainframepublisher)
+ - [pure\_pursuit\_controller](#pure_pursuit_controller)
+ - [stanley\_controller](#stanley_controller)
+ - [vehicle\_controller](#vehicle_controller)
+ - [velocity\_controller](#velocity_controller)
+
+## Overview
+
+The vehicle agent is split into three major components: [Perception](#Perception), [Planning](#Planning)
+and [Acting](#Acting).
+A separate node is responsible for the [visualization](#Visualization).
+The topics published by the Carla bridge can be
+found [here](https://carla.readthedocs.io/projects/ros-bridge/en/latest/ros_sensors/).\
+The messages necessary to control the vehicle via the Carla bridge can be
+found [here](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg).
+
+The miro-board can be found [here](https://miro.com/welcomeonboard/a1F0d1dya2FneWNtbVk4cTBDU1NiN3RiZUIxdGhHNzJBdk5aS3N4VmdBM0R5c2Z1VXZIUUN4SkkwNHpuWlk2ZXwzNDU4NzY0NTMwNjYwNzAyODIzfDI=?share_link_id=785020837509).
+![Architecture overview](../assets/overview.jpg)*Connections between nodes visualized*
+
+![Department node overview](../assets/research_assets/node_path_ros.png)*In- and outgoing topics for every node of the departments*
+
+## Perception
+
+The perception is responsible for the efficient conversion of raw sensor and map data into a useful
+environment representation that can be used by the [Planning](#Planning) for further processing.
+It provides localization of the agent, filtering noise from sensor data, preconditions images for further usage in other nodes and detects certain points of interest (at the moment only traffic lights).
+
+Further information regarding the perception can be found [here](../perception/README.md).
+Research for the perception can be found [here](../research/paf24/perception/).
+
+In the following, all subscribed and published topics and their corresponding nodes are listed with the format:
+
+- ```name of topic``` \(origin/destination node\) (typo of message) (link to ROS documentation of the message type)
+
+### Vision Node ([vision_node.py](/../paf/code/perception/src/vision_node.py))
+
+Evaluates sensor data to detect and classify objects around the ego vehicle.
+Other road users and objects blocking the vehicle's path are recognized (most of the time).
+Recognized traffic lights get cut out from the image and made available for further processing.
+
+Subscriptions:
+
+- ```/paf/hero/Center/dist_array``` \(/lidar_distance\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```/carla/hero/Center/image``` \(/carla_ros_bridge\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```/carla/hero/Back/image``` \(/carla_ros_bridge\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```/carla/hero/Left/image``` \(/carla_ros_bridge\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```/carla/hero/Right/image``` \(/carla_ros_bridge\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+
+Publishes:
+
+- ```/paf/hero/Center/segmented_image``` \(/rviz\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```/paf/hero/Back/segmented_image``` \(/rviz\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```/paf/hero/Left/segmented_image``` \(/rviz\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```/paf/hero/Right/segmented_image``` \(/rviz\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```/paf/hero/Center/object_distance``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+- ```/paf/hero/Back/object_distance``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+- ```/paf/hero/Left/object_distance``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+- ```/paf/hero/Right/object_distance``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+- ```/paf/hero/Center/segmented_traffic_light``` \(/TrafficLightNode\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```/paf/hero/Back/segmented_traffic_light``` \(/TrafficLightNode\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```/paf/hero/Left/segmented_traffic_light``` \(/TrafficLightNode\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```/paf/hero/Right/segmented_traffic_light``` \(/TrafficLightNode\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+
+### Traffic Light Detection ([traffic_light_node.py](/../paf/code/perception/src/traffic_light_node.py))
+
+Recognizes traffic lights and what they are showing at the moment.
+In particular traffic lights that are relevant for the correct traffic behavior of the ego vehicle,
+are recognized early and reliably.
+
+Subscriptions:
+
+- ```/paf/hero/Center/segmented_traffic_light``` \(/VisionNode\) ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+
+Publishes:
+
+- ```/paf/hero/Center/traffic_light_state``` \(/behavior_agent\) ([perception/TrafficLightState](/../paf/code/perception/msg/TrafficLightState.msg))
+- ```/paf/hero/Center/traffic_light_y_distance``` \(/behavior_agent\) ([std_msgs/Int16](https://docs.ros.org/en/api/std_msgs/html/msg/Int16.html))
+
+### Position Heading Node ([position_heading_publisher_node.py](/../paf/code/perception/src/position_heading_publisher_node.py))
+
+Calculates the current_pos (Location of the car) and current_heading (Orientation of the car around the Z- axis).
+
+Subscriptions:
+
+- ```/carla/hero/OpenDRIVE``` \(/carla_ros_bridge\) ([sensor_msgs/String](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/String.html))
+- ```/carla/hero/IMU``` \(/carla_ros_bridge\) ([sensor_msgs/Imu](https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/Imu.html))
+- ```/carla/hero/GPS``` \(/carla_ros_bridge\) ([sensor_msgs/NavSatFix](https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/NavSatFix.html))
+- ```/paf/hero/kalman_pos``` \(/kalman_filter_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/paf/hero/kalman_heading``` \(/kalman_filter_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+Publishes:
+
+- ```/paf/hero/unfiltered_heading``` \(no subscriber at the moment\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/unfiltered_pos``` \(/kalman_filter_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/paf/hero/current_pos``` \(/pure_pursuit_controller, /stanley_controller, /MotionPlanning, /ACC, /MainFramePublisher, /GlobalPlanDistance, /position_heading_publisher_node, /curr_behavior \) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/paf/hero/current_heading``` \(/stanley_controller, /behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+### Global distances ([global_plan_distance_publisher.py](/../paf/code/perception/src/global_plan_distance_publisher.py))
+
+Subscriptions:
+
+- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/carla/hero/global_plan``` \(/ \) ([ros_carla_msgs/msg/CarlaRoute](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaRoute.msg))
+
+Publishes:
+
+- ```/paf/hero/waypoint_distance``` \(/MotionPlanning, /behavior_agent\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html))
+- ```/paf/hero/lane_change_distance``` \(/MotionPlanning, /behavior_agent\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg))
+
+### Kalman filtering ([kalman_filter.py](/../paf/code/perception/src/kalman_filter.py))
+
+Subscriptions:
+
+- ```/carla/hero/OpenDRIVE``` \(/carla_ros_bridge\) ([sensor_msgs/String](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/String.html))
+- ```/carla/hero/IMU``` \(/carla_ros_bridge\) ([sensor_msgs/Imu](https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/Imu.html))
+- ```/carla/hero/GPS``` \(/carla_ros_bridge\) ([sensor_msgs/NavSatFix](https://docs.ros.org/en/noetic/api/sensor_msgs/html/msg/NavSatFix.html))
+- ```/paf/hero/unfiltered_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+
+Publishes:
+
+- ```/paf/hero/kalman_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/paf/hero/kalman_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+### Localization
+
+Provides corrected accurate position, direction and speed of the ego vehicle. For this to be achived the
+
+- [Position Heading Node](#position-heading-node-position_heading_publisher_nodepy)
+- [Kalman filtering](#kalman-filtering) and
+- [Coordinate Transformation](/../paf/code/perception/src/coordinate_transformation.py)
+
+classes are used.
+
+## Planning
+
+The planning uses the data from the [Perception](#Perception) to find a path on which the ego vehicle can safely reach its destination. It also detects situations and reacts accordingly in traffic. It publishes signals such as a trajecotry or a target speed to acting.
+
+Further information regarding the planning can be found [here](../planning/README.md).
+Research for the planning can be found [here](../research/planning/README.md).
+
+### PrePlaner ([global_planner.py](/../paf/code/planning/src/global_planner/global_planner.py))
+
+Uses information from the map and the path specified by CARLA to find a first concrete path to the next intermediate point. More about it can be found [here](../planning/Global_Planner.md).
+
+Subscriptions:
+
+- ```/carla/hero/OpenDRIVE``` \(/carla_ros_bridge\) ([sensor_msgs/String](https://docs.ros.org/en/melodic/api/std_msgs/html/msg/String.html))
+- ```/carla/hero/global_plan``` \(/ \) ([ros_carla_msgs/msg/CarlaRoute](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaRoute.msg))
+- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+
+Publishes:
+
+- ```/paf/hero/trajectory_global``` \(/ACC, /MotionPlanning\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html))
+- ```/paf/hero/speed_limits_OpenDrive``` \(/ACC\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+
+### Behavior Agent ([behavior_agent](/../paf/code/planning/src/behavior_agent/))
+
+Decides which speed is the right one to pass through a certain situation and
+also checks if an overtake is necessary.
+Everything is based on the data from the Perception [Perception](#Perception). More about the behavior tree can be found [here](../planning/Behavior_tree.md)
+
+Subscriptions:
+
+[topics2blackboard.py](/../paf/code/planning/src/behavior_agent/behaviours/topics2blackboard.py)
+
+- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg))
+- ```/paf/hero/slowed_by_car_in_front``` \(/\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html))
+- ```/paf/hero/waypoint_distance``` \(/GlobalPlanDistance\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html))
+- ```/paf/hero/stop_sign``` \(/\) ([mock/Stop_sign](/../paf/code/mock/msg/Stop_sign.msg))
+- ```/paf/hero/Center/traffic_light_state``` \(/TrafficLightNode\) ([perception/TrafficLightState](/../paf/code/perception/msg/TrafficLightState.msg))
+- ```/paf/hero/Center/traffic_light_y_distance``` \(/TrafficLightNode\) ([std_msgs/Int16](https://docs.ros.org/en/api/std_msgs/html/msg/Int16.html))
+- ```/paf/hero/max_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/speed_limit``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/lane_change_distance``` \(/GlobalPlanDistance\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg))
+- ```/paf/hero/collision``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/overtake_success``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/oncoming``` \(/CollisionCheck\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/target_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+Publishes:
+
+[maneuvers.py](/../paf/code/planning/src/behavior_agent/behaviours/maneuvers.py)
+
+- ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html))
+- ```/paf/hero/unstuck_distance``` \(/ACC, /MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/unstuck_flag``` \(/ACC\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html))
+
+[intersection.py](/../paf/code/planning/src/behavior_agent/behaviours/intersection.py)
+
+- ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html))
+
+[lane_change.py](/../paf/code/planning/src/behavior_agent/behaviours/lane_change.py)
+
+- ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html))
+
+[meta.py](/../paf/code/planning/src/behavior_agent/behaviours/meta.py)
+
+- ```/paf/hero/max_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+[overtake.py](/../paf/code/planning/src/behavior_agent/behaviours/overtake.py)
+
+- ```/paf/hero/curr_behavior``` \(/MotionPlanning, /vehicle_controller\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html))
+
+### [Local Planning](../planning/Local_Planning.md)
+
+It consists of three components:
+
+- [Collision Check](../planning//Collision_Check.md): Checks for collisions based on objects recieved from [Perception](#perception)
+- [ACC](../planning/ACC.md): Generates a new speed based on a possible collision recieved from Collision Check and speedlimits recieved from [Global Planner](#global-planning)
+- [Motion Planning](../planning/motion_planning.md): Decides the target speed and modifies trajectory if signal recieved from [Behavior Agent](#behavior-agent-behavior_agent)
+
+Subscriptions:
+
+[ACC.py](/../paf/code/planning/src/local_planner/ACC.py)
+
+- ```/paf/hero/unstuck_flag``` \(/behavior_agent\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html))
+- ```/paf/hero/unstuck_distance``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg))
+- ```/paf/hero/speed_limits_OpenDrive``` \(/PrePlanner\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+- ```/paf/hero/trajectory_global``` \(/PrePlanner\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html))
+- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/paf/hero/collision``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+
+[collision_check.py](/../paf/code/planning/src/local_planner/collision_check.py)
+
+- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg))
+- ```/paf/hero/Center/object_distance``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+
+[motion_planning.py](/../paf/code/planning/src/local_planner/motion_planning.py)
+
+- ```/paf/hero/spawn_car``` \(/\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/speed_limit``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg))
+- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/trajectory_global``` \(/PrePlanner\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html))
+- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/paf/hero/curr_behavior``` \(/behavior_agent\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html))
+- ```/paf/hero/unchecked_emergency``` \(/\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html))
+- ```/paf/hero/acc_velocity``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/waypoint_distance``` \(/GlobalPlanDistance\) ([geographic_msgs/WayPoint](https://docs.ros.org/en/melodic/api/geographic_msgs/html/msg/WayPoint.html))
+- ```/paf/hero/lane_change_distance``` \(/GlobalPlanDistance\) ([perception/msg/LaneChange](/../paf/code/perception/msg/LaneChange.msg))
+- ```/paf/hero/collision``` \(/CollisionCheck\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+- ```/paf/hero/Center/traffic_light_y_distance``` \(/TrafficLightNode\) ([std_msgs/Int16](https://docs.ros.org/en/api/std_msgs/html/msg/Int16.html))
+- ```/paf/hero/unstuck_distance``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/current_wp``` \(/ACC\) ([std_msgs/Float32](https://docs.ros.org/en/api/std_msgs/html/msg/Float32.html))
+
+Publishes:
+
+[ACC.py](/../paf/code/planning/src/local_planner/ACC.py)
+
+- ```/paf/hero/acc_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/current_wp``` ([std_msgs/Float32](https://docs.ros.org/en/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/speed_limit``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+[collision_check.py](/../paf/code/planning/src/local_planner/collision_check.py)
+
+- ```/paf/hero/emergency``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html))
+- ```/paf/hero/collision``` \(/ACC, /MotionPlanning\) ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+- ```/paf/hero/oncoming``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+[motion_planning.py](/../paf/code/planning/src/local_planner/motion_planning.py)
+
+- ```/paf/hero/trajectory``` \(/pure_pursuit_controller\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html))
+- ```/paf/hero/target_velocity``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/overtake_success``` \(/behavior_agent\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+## Acting
+
+The job of this component is to take the planned trajectory and target-velocities from the [Planning](#Planning) component and convert them into steering and throttle/brake controls for the CARLA-vehicle.
+
+All information regarding research done about acting can be found [here](../research/acting/README.md).
+
+Indepth information about the currently implemented acting Components can be found [here](../acting/README.md)!
+
+### [MainFramePublisher](/../paf/code/acting/src/acting/MainFramePublisher.py)
+
+Subscription:
+
+- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+### [pure_pursuit_controller](/../paf/code/acting/src/acting/pure_pursuit_controller.py)
+
+Calculates steering angles that keep the ego vehicle on the path given by
+the [Local path planning](#Local-path-planning).
+
+Subscription:
+
+- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+Publishes:
+
+- ```/paf/hero/pure_pursuit_steer``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/pure_p_debug``` \(/\) ([acting/msg/Debug](/../paf/code/acting/msg/Debug.msg))
+
+### [stanley_controller](/../paf/code/acting/src/acting/stanley_controller.py)
+
+Calculates steering angles that keep the ego vehicle on the path given by
+the [Local path planning](#Local-path-planning).
+
+Subscription:
+
+- ```/paf/hero/trajectory_global``` \(/PrePlanner\) ([nav_msgs/Path](https://docs.ros.org/en/noetic/api/nav_msgs/html/msg/Path.html))
+- ```/paf/hero/current_pos``` \(/position_heading_publisher_node\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/paf/hero/current_heading``` \(/position_heading_publisher_node\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+Publishes:
+
+- ```/paf/hero/stanley_steer``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/stanley_debug``` \(/\) ([acting/msg/StanleyDebug](/../paf/code/acting/msg/StanleyDebug.msg))
+
+### [vehicle_controller](/../paf/code/acting/src/acting/vehicle_controller.py)
+
+Subscription:
+
+- ```/paf/hero/curr_behavior``` \(/behavior_agent\) ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html))
+- ```/paf/hero/emergency``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html))
+- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([geometry_msgs/PoseStamped](https://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/PoseStamped.html))
+- ```/paf/hero/throttle``` \(/velocity_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/brake``` \(/velocity_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/reverse``` \(/velocity_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html))
+- ```/paf/hero/pure_pursuit_steer``` \(/pure_pursuit_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/stanley_steer``` \(/pure_pursuit_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+
+Publishes:
+
+- ```/carla/hero/vehicle_control_cmd``` \(/\) ([ros_carla_msgs/msg/CarlaEgoVehicleControl](https://github.com/carla-simulator/ros-carla-msgs/blob/master/msg/CarlaEgoVehicleControl.msg))
+- ```/carla/hero/status``` \(/\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html))
+- ```/paf/hero/controller``` \(/\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/emergency``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html))
+
+### [velocity_controller](/../paf/code/acting/src/acting/velocity_controller.py)
+
+Calculates acceleration values to drive the target-velocity given by the [Local path planning](#Local-path-planning).
+
+For further indepth information about the currently implemented Vehicle Controller click [here](../acting/vehicle_controller.md)
+
+Subscription:
+
+- ```/paf/hero/target_velocity``` \(/MotionPlanning\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/carla/hero/Speed``` \(/carla_ros_bridge\) ([ros_carla_msgs/msg/CarlaSpeedometer](https://github.com/carla-simulator/ros-carla-msgs/blob/leaderboard-2.0/msg/CarlaSpeedometer.msg))
+
+Publishes:
+
+- ```/paf/hero/throttle``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/brake``` \(/vehicle_controller\) ([std_msgs/Float32](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32.html))
+- ```/paf/hero/reverse``` \(/vehicle_controller\) ([std_msg/Bool](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Bool.html))
diff --git a/doc/general/architecture.md b/doc/general/architecture_planned.md
similarity index 86%
rename from doc/general/architecture.md
rename to doc/general/architecture_planned.md
index f8eaf839..1d6fd803 100644
--- a/doc/general/architecture.md
+++ b/doc/general/architecture_planned.md
@@ -3,24 +3,25 @@
**Summary:** This page gives an overview over the planned general architecture of the vehicle agent.
The document contains an overview over all [nodes](#overview) and [topics](#topics).
-- [Planned architecture of vehicle agent](#planned-architecture-of-vehicle-agent)
- - [Overview](#overview)
- - [Perception](#perception)
- - [Obstacle Detection and Classification](#obstacle-detection-and-classification)
- - [Traffic Light Detection](#traffic-light-detection)
- - [Localization](#localization)
- - [Planning](#planning)
- - [Global Planning](#global-planning)
- - [Decision Making](#decision-making)
- - [Local Planning](#local-planning)
- - [Collision Check](#collision-check)
- - [ACC](#acc)
- - [Motion Planning](#motion-planning)
- - [Acting](#acting)
- - [Path following with Steering Controllers](#path-following-with-steering-controllers)
- - [Velocity control](#velocity-control)
- - [Vehicle controller](#vehicle-controller)
- - [Visualization](#visualization)
+- [Overview](#overview)
+- [Perception](#perception)
+ - [Vision Node](#vision-node)
+ - [Traffic Light Detection](#traffic-light-detection)
+ - [Position Heading Node](#position-heading-node)
+ - [Distance to Objects](#distance-to-objects)
+ - [Localization](#localization)
+- [Planning](#planning)
+ - [Global Planning](#global-planning)
+ - [Decision Making](#decision-making)
+ - [Local Planning](#local-planning)
+ - [Collision Check](#collision-check)
+ - [ACC](#acc)
+ - [Motion Planning](#motion-planning)
+- [Acting](#acting)
+ - [Path following with Steering Controllers](#path-following-with-steering-controllers)
+ - [Velocity control](#velocity-control)
+ - [Vehicle controller](#vehicle-controller)
+- [Visualization](#visualization)
## Overview
@@ -28,12 +29,13 @@ The vehicle agent is split into three major components: [Perception](#Perception
and [Acting](#Acting).
A separate node is responsible for the [visualization](#Visualization).
The topics published by the Carla bridge can be
-found [here](https://carla.readthedocs.io/projects/ros-bridge/en/latest/ros_sensors/).
-The msgs necessary to control the vehicle via the Carla bridge can be
-found [here](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg)
+found [here](https://carla.readthedocs.io/projects/ros-bridge/en/latest/ros_sensors/).\
+The messages necessary to control the vehicle via the Carla bridge can be
+found [here](https://carla.readthedocs.io/en/0.9.8/ros_msgs/#CarlaEgoVehicleControlmsg).\
-![Architecture overview](../assets/overview.jpg)
The miro-board can be found [here](https://miro.com/welcomeonboard/a1F0d1dya2FneWNtbVk4cTBDU1NiN3RiZUIxdGhHNzJBdk5aS3N4VmdBM0R5c2Z1VXZIUUN4SkkwNHpuWlk2ZXwzNDU4NzY0NTMwNjYwNzAyODIzfDI=?share_link_id=785020837509).
+![Architecture overview](../assets/overview.jpg "Connections between nodes visualized")
+![Department node overview](../assets/research_assets/node_path_ros.png "In- and outgoing topics for every node of the departments")
## Perception
@@ -43,7 +45,7 @@ environment representation that can be used by the [Planning](#Planning) for fur
Further information regarding the perception can be found [here](../perception/README.md).
Research for the perception can be found [here](../research/perception/README.md).
-### Obstacle Detection and Classification
+### Vision Node
Evaluates sensor data to detect and classify objects around the ego vehicle.
Other road users and objects blocking the vehicle's path are recognized.
@@ -52,17 +54,28 @@ In the case of dynamic objects, an attempt is made to recognize the direction an
Subscriptions:
-- ```radar``` ([sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html))
- ```lidar``` ([sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html))
- ```rgb_camera``` ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
- ````gnss```` ([sensor_msgs/NavSatFix](https://carla.readthedocs.io/projects/ros-bridge/en/latest/ros_sensors/))
- ```map``` ([std_msgs/String](https://docs.ros.org/en/api/std_msgs/html/msg/String.html))
+- ```radar``` ([sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html)) SOON TO COME
Publishes:
- ```obstacles``` (Custom msg:
obstacle ([vision_msgs/Detection3DArray Message](http://docs.ros.org/en/api/vision_msgs/html/msg/Detection3DArray.html))
and its classification ([std_msgs/String Message](http://docs.ros.org/en/noetic/api/std_msgs/html/msg/String.html)))
+- ```segmented_image``` ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+ - /paf/hero/Center/segmented_image
+ - /paf/hero/Back/segmented_image
+ - /paf/hero/Left/segmented_image
+ - /paf/hero/Right/segmented_image
+- ```segmented_traffic_light``` ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
+- ```object_distance``` ([sensor_msgs/Float32MultiArray](https://docs.ros.org/en/noetic/api/std_msgs/html/msg/Float32MultiArray.html))
+ - /paf/hero/Center/object_distance
+ - /paf/hero/Back/object_distance
+ - /paf/hero/Left/object_distance
+ - /paf/hero/Right/object_distance
### Traffic Light Detection
@@ -84,6 +97,14 @@ Publishes:
position ([geometry_msgs/Pose Message](http://docs.ros.org/en/noetic/api/geometry_msgs/html/msg/Pose.html)),
distance_to_stop_line ([std_msgs/Float64 Message](http://docs.ros.org/en/api/std_msgs/html/msg/Float64.html)))
+### Position Heading Node
+
+There are currently no planned improvements of the Position Heading Node.
+
+### Distance to Objects
+
+There are currently no planned improvements for Distance to Objects.
+
### Localization
Provides corrected accurate position, direction and speed of the ego vehicle
diff --git a/doc/perception/radar_node.md b/doc/perception/radar_node.md
new file mode 100644
index 00000000..26783bc2
--- /dev/null
+++ b/doc/perception/radar_node.md
@@ -0,0 +1,36 @@
+# Radar Node
+
+**Summary:** This page explains what the radar sensor does.
+
+- [Radar offsets](#radar-offsets)
+- [Radar specification](#radar-specification)
+- [Radar data output for each detected point](#radar-data-output-for-each-detected-point)
+- [Todo](#todo)
+
+## Radar offsets
+
+- x: 2
+- y: 0
+- z: 0.7
+
+## Radar specification
+
+- points per second: 1500 points generated by all lasers per second
+- maximum range: 100 meters
+- horizontal fov: 30 degrees
+- vertical fov: 30 degrees
+
+## Radar data output for each detected point
+
+- x
+- y
+- z
+- Range
+- Velocity
+- AzimuthAngle
+- ElevationAngle
+
+## Todo
+
+- Discuss further processing of radar data
+- Combine lidar, radar and camera data
diff --git a/doc/research/README.md b/doc/research/README.md
index 1b2caa70..26cea173 100644
--- a/doc/research/README.md
+++ b/doc/research/README.md
@@ -52,3 +52,4 @@ In addition to the research of the previous years, the following resources can b
- [Awesome 3D Object Detection for Autonomous Driving](https://github.com/PointsCoder/Awesome-3D-Object-Detection-for-Autonomous-Driving)
- [Microsoft Autonomous Driving Cookbook](https://github.com/microsoft/AutonomousDrivingCookbook)
- [End-to-End Autonomous Driving](https://github.com/OpenDriveLab/End-to-end-Autonomous-Driving)
+- [UT-ADL/autoware_mini](https://github.com/UT-ADL/autoware_mini)
diff --git a/doc/research/paf24/general/current_state.md b/doc/research/paf24/general/current_state.md
index bffc2432..f5a9d194 100755
--- a/doc/research/paf24/general/current_state.md
+++ b/doc/research/paf24/general/current_state.md
@@ -128,6 +128,8 @@ Here are the raw notes in case misunderstandings have been made when grouping th
### Run 1
+[Link to Video of the Run](https://drive.google.com/file/d/1Hb4arEC5ocfUD2KZh1bNVwRG2hoML8E9/view?usp=drive_link)
+
- Scared to get out of parking spot
- lane not held causing problems when avoiding open car door
- stopping for no apparent reason
@@ -153,6 +155,8 @@ Here are the raw notes in case misunderstandings have been made when grouping th
### Run 2
+[Link to Video of the Run](https://drive.google.com/file/d/1xot90LTNcSYOkLa1sXJJeMFBkXKmFO2x/view?usp=drive_link)
+
- merges without giving way to traffic
- does not respect open car door
- crashes into car in front when going after stop at red light
@@ -168,6 +172,8 @@ Here are the raw notes in case misunderstandings have been made when grouping th
### Run 3
+[Link to Video of the Run](https://drive.google.com/file/d/1ERvN3nGddzuvtRqtIF2PKlFrcMzH2MrA/view?usp=drive_link)
+
- does not give way when exiting a parking spot
- LIDAR detects floor
- trajectory for overtaking is wrong / no overtake needed