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/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/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/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)).