Skip to content

Commit

Permalink
Graph and Global Planning desc
Browse files Browse the repository at this point in the history
  • Loading branch information
johannaschwarz committed Nov 1, 2024
1 parent 495e1d5 commit a19e765
Show file tree
Hide file tree
Showing 4 changed files with 34 additions and 19 deletions.
16 changes: 7 additions & 9 deletions code/planning/src/global_planner/global_planner.py
Original file line number Diff line number Diff line change
@@ -1,17 +1,15 @@
#!/usr/bin/env python
import rospy
import tf.transformations
import ros_compatibility as roscomp
from ros_compatibility.node import CompatibleNode
from xml.etree import ElementTree as eTree

from geometry_msgs.msg import PoseStamped, Pose, Point, Quaternion
import ros_compatibility as roscomp
import rospy
import tf.transformations
from carla_msgs.msg import CarlaRoute # , CarlaWorldInfo
from geometry_msgs.msg import Point, Pose, PoseStamped, Quaternion
from nav_msgs.msg import Path
from std_msgs.msg import String
from std_msgs.msg import Float32MultiArray

from preplanning_trajectory import OpenDriveConverter
from ros_compatibility.node import CompatibleNode
from std_msgs.msg import Float32MultiArray, String

RIGHT = 1
LEFT = 2
Expand All @@ -29,7 +27,7 @@ class PrePlanner(CompatibleNode):
- global Plan: /carla/{role_name}/global_plan
- current agent position: /paf/{role_name}/current_pos
Published topics:
- preplanned trajectory: /paf/{role_name}/trajectory
- preplanned trajectory: /paf/{role_name}/trajectory_global
- prevailing speed limits:/paf/{role_name}/speed_limits_OpenDrive
"""

Expand Down
Binary file added doc/assets/research_assets/planning_internal.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
18 changes: 8 additions & 10 deletions doc/planning/Global_Planner.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,11 @@ to the other components of this project (acting, decision making,...).

This component and so most of the documentation was taken from the previous project PAF22 (Authors: Simon Erlbacher, Niklas Vogel)

- [Global Planner](#global-planner)
- [Getting started](#getting-started)
- [Description](#description)
- [Inputs](#inputs)
- [Outputs](#outputs)
- [Testing](#testing)
- [Getting started](#getting-started)
- [Description](#description)
- [Inputs](#inputs)
- [Outputs](#outputs)
- [Testing](#testing)

## Getting started

Expand All @@ -25,8 +24,7 @@ No extra installation needed.

## Description

First the global planner is responsible for collecting and preparing all data from the leaderboard and other intern
components that is needed for the preplanning component.
First the global planner is responsible for collecting and preparing all data from the leaderboard and other internal components that is needed for the preplanning component.

To get an instance of the OpenDriveConverter (ODC) the received OpenDrive Map prevailing in String format
has to be converted. In our case we use the
Expand Down Expand Up @@ -56,8 +54,8 @@ The received agent spawn position is valid if it´s closer to the first waypoint
parameter expresses. This is necessary to prevent unwanted behaviour in the startup phase where the
current agent position is faulty.

When the ODC got initialised, the current agent position is received and the global plan is obtained from
the leaderboard the trajectory can be calculated by iterating through the global route and passing it to the ODC.
When the ODC is initialised, the current agent position is received and the global plan is obtained from
the leaderboard. The trajectory can be calculated by iterating through the global route and passing it to the ODC.
After smaller outliners are removed the x and y coordinates as well as the yaw-orientation and the prevailing
speed limits can be acquired from the ODC in the following form:

Expand Down
19 changes: 19 additions & 0 deletions doc/research/paf24/planning/local_v_global_planning.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
# Relation beteween local and global planning

Communication between Global and Local Planning is done via ros topics. Here is a graph showing the relation between the nodes.

- Global Planning: PrePlanner
- Local Planning: ACC (Adaptive Cruise Control), CollisionCheck, MotionPlanning

![Graph relation](/doc/assets/research_assets/planning_internal.png)

## Global Planning

Global planning consits of the PrePlanner Node and the OpenDriveConverter.

- OpenDriveConverter: The class is primarily used to process OpenDrive maps and extract relevant information needed for trajectory planning.
- PrePlanner Node: The PrePlanner node is responsible for creating a trajectory out of an OpenDrive Map with the belonging road options.
- the `/paf/hero/trajectory_global` topic published is used internally for the preplanned trajectory.

## Local Planning

0 comments on commit a19e765

Please sign in to comment.