Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

373 unstuck behavior #425

Merged
merged 11 commits into from
Nov 3, 2024
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
29 changes: 17 additions & 12 deletions code/planning/src/local_planner/motion_planning.py
Original file line number Diff line number Diff line change
Expand Up @@ -232,15 +232,16 @@ def change_trajectory(self, distance_obj):
Args:
distance_obj (float): distance to overtake object
"""
pose_list = self.trajectory.poses
pose_list = self.trajectory.poses #vehicle's planned path.

# Only use fallback
self.overtake_fallback(distance_obj, pose_list)
self.__overtake_status = 1
self.overtake_fallback(distance_obj, pose_list) #likely implements a simpler, predefined maneuver for overtaking, which adjusts the trajectory if more sophisticated planning is unavailable or as a safety fallback option.
self.__overtake_status = 1 #overtake successfully planed
self.overtake_success_pub.publish(self.__overtake_status)
return

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

🛠️ Refactor suggestion

Add error handling and validation in change_trajectory method.

The method needs additional safeguards:

  1. Validate pose_list is not empty
  2. Verify the success of overtake_fallback before setting __overtake_status
  3. Add error handling for potential exceptions during trajectory modification
 def change_trajectory(self, distance_obj):
+    if not self.trajectory or not self.trajectory.poses:
+        self.logwarn("No trajectory available for modification")
+        return
     pose_list = self.trajectory.poses
 
-    self.overtake_fallback(distance_obj, pose_list)
-    self.__overtake_status = 1
+    try:
+        self.overtake_fallback(distance_obj, pose_list)
+        self.__overtake_status = 1
+    except Exception as e:
+        self.logerr(f"Failed to modify trajectory: {e}")
+        self.__overtake_status = -1
     self.overtake_success_pub.publish(self.__overtake_status)
     return

Committable suggestion skipped: line range outside the PR's diff.

def overtake_fallback(self, distance, pose_list, unstuck=False):
def overtake_fallback(self, distance, pose_list, unstuck=False): #his method constructs a temporary path around an obstacle based on the current location, intended distance to overtake, and a choice between two different lateral offsets depending on whether the vehicle is in an “unstuck” situation.
#codepart for overtake behaviour
currentwp = self.current_wp
normal_x_offset = 2
unstuck_x_offset = 3 # could need adjustment with better steering
Expand Down Expand Up @@ -280,6 +281,8 @@ def overtake_fallback(self, distance, pose_list, unstuck=False):
pos.header.frame_id = "global"
pos.pose = pose
result.append(pos)

#code part for returning back on the lane
path = Path()
path.header.stamp = rospy.Time.now()
path.header.frame_id = "global"
Expand Down Expand Up @@ -440,10 +443,10 @@ def __set_acc_speed(self, data: Float32):

def __set_curr_behavior(self, data: String):
self.__curr_behavior = data.data
if data.data == bs.ot_enter_init.name:
if np.isinf(self.__collision_point):
self.__overtake_status = -1
self.overtake_success_pub.publish(self.__overtake_status)
if data.data == bs.ot_enter_init.name: #is beggins overtake manuever
if np.isinf(self.__collision_point): # if no obsticle to overtake
self.__overtake_status = -1 #unsuccessfull or canceled overtake
self.overtake_success_pub.publish(self.__overtake_status) #abandonment of the overtake attempt.
return
self.change_trajectory(self.__collision_point)

Expand Down Expand Up @@ -479,6 +482,7 @@ def get_speed_by_behavior(self, behavior: str) -> float:
speed = self.__get_speed_cruise()
return speed

#manage the speed of the vehicle when it encounters situations where it becomes "stuck"
def __get_speed_unstuck(self, behavior: str) -> float:
global UNSTUCK_OVERTAKE_FLAG_CLEAR_DISTANCE
speed = 0.0
Expand All @@ -488,7 +492,7 @@ def __get_speed_unstuck(self, behavior: str) -> float:
speed = bs.us_stop.speed
elif behavior == bs.us_overtake.name:
pose_list = self.trajectory.poses
if self.unstuck_distance is None:
if self.unstuck_distance is None: # Without knowing the distance to the obstacle, the vehicle cannot safely plan an overtake trajectory.
self.logfatal("Unstuck distance not set")
return speed

Expand All @@ -498,16 +502,16 @@ def __get_speed_unstuck(self, behavior: str) -> float:
)
# self.logfatal(f"Unstuck Distance in mp: {distance}")
# clear distance to last unstuck -> avoid spamming overtake
if distance > UNSTUCK_OVERTAKE_FLAG_CLEAR_DISTANCE:
if distance > UNSTUCK_OVERTAKE_FLAG_CLEAR_DISTANCE: #The method checks if the vehicle has moved a significant distance (UNSTUCK_OVERTAKE_FLAG_CLEAR_DISTANCE) since the last overtake. This prevents repeated overtake attempts when they are unnecessary or unsafe.
self.unstuck_overtake_flag = False
self.logwarn("Unstuck Overtake Flag Cleared")

# to avoid spamming the overtake_fallback
if self.unstuck_overtake_flag is False:
if self.unstuck_overtake_flag is False:
# create overtake trajectory starting 6 meteres before
# the obstacle
# 6 worked well in tests, but can be adjusted
self.overtake_fallback(self.unstuck_distance, pose_list, unstuck=True)
self.overtake_fallback(self.unstuck_distance, pose_list, unstuck=True) #A fallback overtaking path is created to move around the obstacle when necessary.
self.logfatal("Overtake Trajectory while unstuck!")
self.unstuck_overtake_flag = True
self.init_overtake_pos = self.current_pos[:2]
Expand Down Expand Up @@ -661,3 +665,4 @@ def loop(timer_event=None):
pass
finally:
roscomp.shutdown()

147 changes: 147 additions & 0 deletions doc/research/paf24/planning/Unstuck_Overtake Behavior.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,147 @@
# Unstuck/Overtake Behavior

**Summary:** This document analyzes the current unstuck/overtake behavior and reveals several critical issues with the existing implementation.

- [Unstuck behavior](#unstuck-behavior)
- [Key components](#key-components)
- [How unstuck is triggered](#how-unstuck-is-triggered)
- [Overtake behavior](#overtake-behavior)
- [Key components](#key-components)
- [How overtake is triggered](#how-overtake-is-triggered)
- [Relevant rostopics](#relevant-rostopics)
- [Methods overview](#methods-overview)
- [def \_\_set_curr_behavior](#def-set_curr_behavior)
- [def change_trajectory](#def-change_trajectory)
- [def overtake_fallback](#def-overtake_fallback)
Copy link
Contributor

@niklasr22 niklasr22 Nov 3, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

When documenting the motion_planning.py file, I changed the method name from overtake_fallback to generate_overtake_trajectory to better reflect the actual behavior of the method. So it might be good to replace all of the occurrences here as well

- [Overtake behavior issues](#overtake-behavior-issues)
- [Aggressive lane changes](#aggressive-lane-changes)
- [Inadequate collision detection](#inadequate-collision-detection)
- [Improper trajectory planning](#improper-trajectory-planning)
- [Unstuck behavior issues](#unstuck-behavior-issues)
- [Potential improvements](#potential-improvements)

---

## Unstuck behavior

The "unstuck" behavior is designed to address situations where the vehicle becomes stuck, perhaps due to obstacles or other vehicles blocking its path.

### Key components

- `self.unstuck_distance`: Tracks the distance to the object causing the blockage, helping the algorithm to determine if an alternative route (overtaking) might be required.
- `self.unstuck_overtake_flag`: Prevents repeated or "spam" overtakes by ensuring that the unstuck overtake only happens once within a specified distance (`UNSTUCK_OVERTAKE_FLAG_CLEAR_DISTANCE`).
- `self.init_overtake_pos`: Saves the position where the unstuck behavior is initiated to prevent excessive overtaking within a short range.
- **Overtaking Logic**: The method `overtake_fallback` is called within `__get_speed_unstuck`, where a new trajectory is created by offsetting the path to one side, allowing the vehicle to bypass the obstacle and get "unstuck."

### How unstuck is triggered

The method `__get_speed_unstuck` checks the current behavior (e.g., `us_unstuck`), adjusting speed accordingly and invoking `overtake_fallback` if an obstacle is detected and the vehicle is in an "unstuck" situation. `UNSTUCK_OVERTAKE_FLAG_CLEAR_DISTANCE` ensures that once an unstuck maneuver is initiated, it won't be repeated until a certain distance is cleared.

---

## Overtake behavior

The overtake behavior allows the vehicle to safely overtake a slower-moving or stationary vehicle ahead by modifying its trajectory.

### Key components

- `self.__overtake_status`: Manages the status of overtaking, where `1` indicates an active overtake, while `-1` signals that overtaking isn't required.
- `change_trajectory`: Initiates the overtake by calling `overtake_fallback` when it detects a collision point or slow-moving vehicle within a certain range. This method also publishes the updated `__overtake_status` to signal other systems of the change.
- `overtake_fallback`: Calculates a new trajectory path that offsets the vehicle by a certain distance (`normal_x_offset`) to safely pass the obstacle. The adjusted path uses the Rotation library to align the offset with the vehicle’s heading, creating a smooth path around the obstacle.

### How overtake is triggered

The method `__set_curr_behavior` monitors the vehicle’s behavior, triggering an overtake when `ot_enter_init` behavior is detected and if an obstacle or collision point is near. It then calls `change_trajectory` to modify the route. Speed adjustments specific to overtaking are handled in `__get_speed_overtake`, where the vehicle might slow down (e.g., `ot_enter_slow`) or proceed at normal speed after overtaking (e.g., `ot_leave`).

---

## Relevant rostopics

- `overtake_success`
- `unstuck_distance`
- _#TODO: need to continue_

---

## Methods overview

### `def __set_curr_behavior(self, data: String)`

**How it works:**

- **If beginning an overtake maneuver:**
- If no obstacle to overtake:
- Unsuccessful or canceled overtake
- Publish abandonment of the overtake attempt.
- Otherwise:
- Change trajectory

- **Infinity as "No Collision Detected"**: Setting `self.__collision_point` to infinity (`np.inf`) means "no collision detected." So, checking if `np.isinf(self.__collision_point)` effectively asks, "Is there no obstacle or point that needs an overtake?"

- `self.__overtake_status = -1`: Unsuccessful or canceled overtake
- `self.__overtake_status = 1`: Overtake should take place

**Questions:**

1. Who tells the function the behavior status?
2. If the function has already become an overtake status, why should we check if there is actually an object to overtake?

---

### `def change_trajectory(self, distance_obj)`

**Description**: Updates trajectory for overtaking and converts it to a new `Path` message.

- **Args**: `distance_obj` (float): Distance to overtake object
- **Outcome**: Publishes overtake success status

**Questions:**

1. What does the success status for overtake mean? It seems like it publishes that an overtake takes place but does not notify if the maneuver was successful.

---

### `def overtake_fallback(self, distance, pose_list, unstuck=False)`

**Description**: Constructs a temporary path around an obstacle based on the current location, intended distance to overtake, and a choice between two different lateral offsets depending on whether the vehicle is in an "unstuck" situation.

1. **Pick Path Points Around the Obstacle**: Selects a section of the path around the vehicle’s current position and the obstacle it needs to overtake. If the vehicle is stuck, it picks a larger section to give it more room to maneuver.
2. **Shift Path to the Side**: Moves this section of the path slightly to the side (left or right, depending on the vehicle's heading) to avoid the obstacle. If the vehicle is in a “stuck” situation, it shifts it a bit more to give it extra clearance.
3. **Create the New Path**: Converts the shifted points into a path format that the vehicle’s navigation system can understand and follow.
4. **Combine with Original Path**: Merges this temporary bypass with the original path, so the vehicle can return to its route after it passes the obstacle.

---

## Overtake behavior issues

### Aggressive lane changes

The vehicle exhibits aggressive lane changes, leading to emergency stops to avoid oncoming traffic. This behavior suggests that the decision-making logic for overtaking does not adequately assess the surrounding traffic conditions before executing maneuvers.

### Inadequate collision detection

The vehicle fails to avoid obstacles, such as open car doors or stationary vehicles, indicating that the collision detection mechanisms are either insufficient or not effectively integrated into the overtaking logic.

### Improper trajectory planning

The trajectory generated for overtaking often leads to incorrect paths, such as attempting to overtake trees or parked cars without considering oncoming traffic. A better filtering and validation of potential overtaking targets is needed.

Comment on lines +125 to +136
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

⚠️ Potential issue

Critical safety issues need immediate attention.

The documented issues with aggressive lane changes, inadequate collision detection, and improper trajectory planning present significant safety risks:

  1. Emergency stops due to aggressive lane changes
  2. Failure to avoid obstacles
  3. Incorrect path planning around static objects

These issues require immediate attention and should be tracked with high-priority tickets. Consider implementing:

  1. A pre-overtake validation phase
  2. Enhanced obstacle classification
  3. Multi-stage trajectory planning with safety checks

Would you like me to create GitHub issues for tracking these safety-critical improvements?

---

## Unstuck behavior issues

- The vehicle gets stuck multiple times and exhibits erratic behavior when trying to get unstuck.
- The vehicle's aggressive lane-holding behavior after being unstuck.
- After collisions, the vehicle often fails to resume movement, indicating a lack of recovery logic post-collision.

---

## Potential improvements

- `def change_trajectory`: Consider implementing a more sophisticated trajectory planning algorithm that considers dynamic obstacles and traffic conditions rather than relying on a fallback method. Verify that the area into which the vehicle is moving is clear of obstacles and oncoming traffic.
- `def overtake_fallback`: Instead of fixed offsets for unstuck and normal situations, consider dynamically calculating offsets based on current speed, vehicle dimensions, and surrounding traffic conditions.
- `__get_speed_unstuck`: Include checks for nearby vehicles and their speeds. Make `UNSTUCK_OVERTAKE_FLAG_CLEAR_DISTANCE` dynamic.
- `__check_emergency`: Currently, it only considers whether the vehicle is in a parking behavior state. Expand this method to evaluate various emergency conditions (e.g., obstacles detected by sensors) and initiate appropriate responses (e.g., stopping or rerouting).
Copy link
Contributor

@niklasr22 niklasr22 Nov 3, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

__check_emergency never gets called (#413) and i think eventually, we should remove it entirely. But for now I think it is ok to mention it here

- `get_speed_by_behavior`: Consider feedback from sensors regarding current traffic conditions.
- `__calc_corner_points`: Consider a more intelligent approach rather than relying on simple angle thresholds.

Comment on lines +147 to +155
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

🛠️ Refactor suggestion

Enhance improvement suggestions with concrete implementation details

The potential improvements section would benefit from:

  1. Specific implementation examples for each suggestion
  2. Acceptance criteria for improvements
  3. Priority levels for each enhancement
  4. Dependencies between improvements

Consider structuring this section as a roadmap with clear milestones and success metrics.

Would you like me to help create a detailed implementation roadmap for these improvements?

🧰 Tools
🪛 LanguageTool

[uncategorized] ~149-~149: Loose punctuation mark.
Context: ... improvements - def change_trajectory: Consider implementing a more sophistica...

(UNLIKELY_OPENING_PUNCTUATION)


[uncategorized] ~150-~150: Loose punctuation mark.
Context: ...oming traffic. - def overtake_fallback: Instead of fixed offsets for unstuck an...

(UNLIKELY_OPENING_PUNCTUATION)


[uncategorized] ~151-~151: Loose punctuation mark.
Context: ...ffic conditions. - __get_speed_unstuck: Include checks for nearby vehicles and ...

(UNLIKELY_OPENING_PUNCTUATION)


[uncategorized] ~152-~152: Loose punctuation mark.
Context: ...DISTANCEdynamic. -__check_emergency`: Currently, it only considers whether th...

(UNLIKELY_OPENING_PUNCTUATION)


[uncategorized] ~153-~153: Loose punctuation mark.
Context: ...or rerouting). - get_speed_by_behavior: Consider feedback from sensors regardin...

(UNLIKELY_OPENING_PUNCTUATION)


[uncategorized] ~154-~154: Loose punctuation mark.
Context: ...fic conditions. - __calc_corner_points: Consider a more intelligent approach ra...

(UNLIKELY_OPENING_PUNCTUATION)