rodrigoqueiroz / geoscenarioserver

8 stars 1 forks source link

The "Jumping Back" of Vehicles in Simulation #41

Closed mchlswyr closed 11 months ago

mchlswyr commented 3 years ago

Tests

GSS="${HOME}/anm_unreal_sim/submodules/geoscenarioserver" SIM="${HOME}/anm_unreal_sim/submodules/anm_sim_platform"

cleanup_and_exit() { killall python3.8 killall roslaunch

# Cleanup Shared Memory
ipcrm -M 0x0001e240 # 123456
ipcrm -M 0x00051877 # 333943

# Cleanup Semaphores
ipcrm -S 0x000549c5 # 346565
ipcrm -S 0x000e3e39 # 933433

exit 0

}

keyboard_int() { echo "" echo "Press ENTER to exit." }

trap keyboard_int SIGINT

source "${GSS}/catkin_ws/install/opt/ros/lanelet2/setup.bash" --extend python3.8 "${GSS}/GSServer.py" -s 'scenarios/test_scenarios/gs_ringroad_stress_loop.osm' & bash "${SIM}/scripts/launch.bash" 'ring_road_ccw' > simlog.log &

read -p "Press ENTER to exit." cleanup_and_exit



- In each test, some vehicles were removed from `scenarios/test_scenarios/gs_ringroad_stress_loop.osm`
- Each test was only run once, so they only give a feel for the performance
### Test 1: No Lag
- Removed all vehicles except for `vid: 8`
- Average gss delta time was 33.452395/1000 s (33.452 ms)
- Average gsclient delta time was 30.636478/1000 s (30.636 ms)
### Test 2: Slight Lag
- Removed all vehicles except for `vids: 6, 7, 8, 9, 10`
- Average gss delta time was 33.954446/1000 s (33.954 ms)
- Average gsclient delta time was 36.989265/1000 s (36.989 ms)
### Test 3: Noticable Lag
- Removed all vehicles except for `vids: 4, 5, 6, 7, 8, 9, 10`
- Average gss delta time was 42.989064/1000 s (42.989 ms)
- Average gsclient delta time was 56.858391/1000 s (56.858 ms)
### Test 4: Very Laggy
- Didn't remove any vehicles
- Average gss delta time was 67.004617/800 s (83.756 ms)
- Average gsclient delta time was 54.260967/800 s (67.826 ms)

## Issues
- The issue that we would like to focus on is the "jumping back" of the vehicles that is somewhat noticable in **Test 3**, and much more noticable in **Test 4**
mchlswyr commented 3 years ago

Notes

Note 1

Note 2

sync_planner = TickSync(rate=PLANNER_RATE, realtime=True, block=False, verbose=False, label="PP") ...

and removing `return False` in `tick()` in `TickSync.py`:
```py
...
if (drift<0):
    #Too fast. Need to chill.
    if (self.block):
        time.sleep(-drift)      #blocks diff if negative drift
        #self.print('sleep {:.3}'.format(drift))
    else:
        #self.print('skip {:.3}'.format(drift))
        pass#return False            #return false to skip
...

it is easy to notice the "jumping back" effect

Note 3

Note 4

mchlswyr commented 3 years ago

Measuring "Jump Back"

Measuring "Jump Back" in the Python Code

update sim state

self.state.x = x_vector[0] ... if self.reversing: heading *= -1 self.state.yaw = math.degrees(math.atan2(heading[1], heading[0])) % 360

new_pos = np.array([self.state.x, self.state.y])
delta_d = new_pos - old_pos
new_yaw = math.degrees(math.atan2(delta_d[0], delta_d[1])) % 360

yaw_diff = abs(self.state.yaw - new_yaw)
if yaw_diff > 178.2 and yaw_diff < 181.8: # if yaw_diff within 1% of 180
    self.freq += 1

sanity check

...

- `old_pos` is the position just before it is updated
- `self.state.yaw` is placed in the range [0, 360), and is the direction the vehicle is supposed to head in
- `new_pos` is the position after it was updated (after the comment `#update sim state`)
- `delta_d` can be thought of as the "delta distance" in the equation v = d/t, where v is a vector containing the speed in the x- and y-directions
- `new_yaw`, then, is calculated in the exact same way as `self.state.yaw`, but using the change in position (`delta_d`) instead of the velocity
- If the difference between the two yaws in within 1% of 180, then this is assumed to be the "jump back" effect
- A variable `self.freq` is added to each vehicle to keep track of how many times it "jumps back" during the simulation
- In the function `stop_all()` in the file `SimTraffic.py`, I added:
```py
...
for vid in self.vehicles:
    print("VID: %d, FREQ: %d" % (vid, self.vehicles[vid].freq))
    self.vehicles[vid].stop()
...

Results

Test 1

Test 2

Test 3

Test 4

Test 5

Test 6

Conclusion

mchlswyr commented 3 years ago

In Python

mchlswyr commented 3 years ago

update frenet state

self.state.s = self.s_eq(time) ... if yaw_diff > 178.2 and yaw_diff < 181.8: self.freq += 1

if self.plan_change:
    self.count += 1

if old_s > self.state.s:
    self.s += 1

...

- You will find that `self.s == self.freq`
- In other words, if there is "jump back", then `old_s > self.state.s`; the converse isn't true
- `old_s > self.state.s` is what `direction_cost()` does in `CostFunctions.py`
- I've tried to run `direction_cost()` for every trajectory (in `maneuver_feasibility()`):
```py
...
elif c == 'max_long_jerk':
    if max_long_jerk_cost(trajectory, mconfig.max_long_jerk) > 0:
        return False
    #elif c == 'direction':
    #     if direction_cost(trajectory, start_state, target_state) > 0:
    #         return False
    else:
        raise NotImplementedError("Feasibility function {} not implemented".format(c))

if direction_cost(trajectory, start_state, target_state) > 0:
    return False

return True
mchlswyr commented 3 years ago

Changes to Python Code

self.jump_back_count = 0 self.plan_change = False self.plan_change_count = 0 self.tick_diff_one_count = 0 self.min_tick_diff = 100 ... def tick(self, tick_count, delta_time, sim_time): Vehicle.tick(self, tick_count, delta_time, sim_time) self.plan_change = False ... if plan: self.plan_change = True ...

Compute new state

    self.compute_vehicle_state(delta_time, tick_count)

def compute_vehicle_state(self, delta_time, tick_count): ... old_s = self.state.s

    # update frenet state
    self.state.s = self.s_eq(time)

... heading = np.array([y_vector[1], x_vector[1]])

if self.reversing:

    #     heading *= -1
    self.state.yaw = math.degrees(math.atan2(heading[1], heading[0]))

     if old_s > self.state.s:
         self.jump_back_count += 1

         if self.plan_change:
             self.plan_change_count += 1

              if tick_count == (self.reversing + 1):
                  self.tick_diff_one_count += 1

                  self.min_tick_diff = min(self.min_tick_diff, tick_count - self.reversing)

    #sanity check
- In `SimTraffic.py`:
```py
def stop_all(self):
...
    for vid in self.vehicles:
        print(
            "VID: %d, FREQ: %d, COUNT: %d, S: %d, GOOD: %d, TICK_DIFF: %d" %
            (vid, self.vehicles[vid].freq, self.vehicles[vid].count,
            self.vehicles[vid].s, self.vehicles[vid].good_tick_count,
            self.vehicles[vid].min_tick_diff)
        )

    for vid in self.vehicles:
...

Results

mchlswyr commented 3 years ago

Solution 1

Changes to Python Code

Results:

mchlswyr commented 3 years ago

Solution 2

Changes to Python Code

Results:

python3.8 GSServer.py -s scenarios/test_scenarios/gs_ringroad_stress_loop.osm
...
I0226 16:30:51.833491 32195 SDVPlanner.py:93] PLANNER PROCESS START for Vehicle 2
10 is leading. Distance 5.705784213721145, time gap inf
9 is leading. Distance 25.543431419976557, time gap inf
8 is leading. Distance 5.6204556900652065, time gap inf
E0226 16:30:51.853212 32190 ManeuverModels.py:395] No feasible trajectory to select
I0226 16:30:51.858024 32194 SDVPlanner.py:93] PLANNER PROCESS START for Vehicle 6
I0226 16:30:51.887776 32196 SDVPlanner.py:93] PLANNER PROCESS START for Vehicle 1
3 is leading. Distance 11.11835434773866, time gap inf
7 is leading. Distance 5.197694971518814, time gap inf
5 is leading. Distance 6.298504413839746, time gap inf
2 is leading. Distance 11.19746881928128, time gap inf
I0226 16:30:52.038504 32159 Vehicle.py:190] ++++++++++VID: 3, DIST: 0.000012++++++++++
I0226 16:30:52.039570 32159 Vehicle.py:190] ++++++++++VID: 10, DIST: 0.000016++++++++++
I0226 16:30:52.040146 32159 Vehicle.py:190] ++++++++++VID: 9, DIST: 0.000027++++++++++
I0226 16:30:52.041012 32159 Vehicle.py:190] ++++++++++VID: 6, DIST: 0.000025++++++++++
I0226 16:30:52.041642 32159 Vehicle.py:190] ++++++++++VID: 2, DIST: 0.000004++++++++++
...
VID: 4, JBC: 0, PLC: 0, TDOC: 0, MTD: 100
VID: 3, JBC: 1, PLC: 1, TDOC: 1, MTD: 1
VID: 5, JBC: 0, PLC: 0, TDOC: 0, MTD: 100
VID: 10, JBC: 1, PLC: 1, TDOC: 1, MTD: 1
VID: 9, JBC: 1, PLC: 1, TDOC: 1, MTD: 1
VID: 8, JBC: 0, PLC: 0, TDOC: 0, MTD: 100
VID: 7, JBC: 0, PLC: 0, TDOC: 0, MTD: 100
VID: 6, JBC: 1, PLC: 1, TDOC: 1, MTD: 1
VID: 2, JBC: 1, PLC: 1, TDOC: 1, MTD: 1
VID: 1, JBC: 0, PLC: 0, TDOC: 0, MTD: 100
...
I0226 16:31:51.837915 32159 GSServer.py:77] TICK_COUNT: 758
I0226 16:31:51.838017 32159 GSServer.py:81] SIMULATION END
...
rodrigoqueiroz commented 3 years ago

Great detailed findings. Question about Solution2: Is the main process (SimTraffic) being blocked while the planners are released to run?

mchlswyr commented 3 years ago

Question about Solution2: Is the main process (SimTraffic) being blocked while the planners are released to run?

Yes, it releases them all at once and is blocked until they all finish.

rodrigoqueiroz commented 3 years ago

We can't block the main process. Simulation will stutter until all planners finish their job. The co-simulator (in this case, unreal) or the subject system (the ADS) will continue running and reading last states as the vehicles, pedestrians, tlight state transitions are paused for a brief moment.

With my recent optimizations over the cost functions and the planning process I believe most of the "jump back" is gone (or significantly reduced). But there is an inherit problem with the planning task that makes it impossible to completely remove it. The more vehicles we add, the more it becomes noticeable.

There is an alternative I would like to discuss in the meeting. There are trade offs, so we will have it as an option. For now. Please, update your tests with the most recent version in the master branch so we have a new baseline.

mchlswyr commented 3 years ago

Code Changes

def compute_vehicle_state(self, delta_time, tick_count): ... old_s = self.state.s old_pos = np.array([self.state.x, self.state.y])

    # update frenet state

... heading = np.array([y_vector[1], x_vector[1]])

if self.motion_plan.reversing:

    #     heading *= -1
    self.state.yaw = math.degrees(math.atan2(heading[1], heading[0]))

    if old_s > self.state.s:
        self.jump_back_count += 1

        new_pos = np.array([self.state.x, self.state.y])
        delta_pos = new_pos - old_pos
        dist = math.sqrt(delta_pos[0]*delta_pos[0] + delta_pos[1]*delta_pos[1])
        self.max_jump_back_dist = max(self.max_jump_back_dist, dist)

        if self.plan_change:
            self.plan_change_count += 1

            self.min_tick_diff = min(self.min_tick_diff, tick_count - self.motion_plan.reversing)

...

- In `sv/SDVPlanner.py`:
```py
def run_planner_process(self, traffic_state_sharr, mplan_sharr, debug_shdata):
...
        state_time = header[2]
        tick_count = header[0]
...
                plan.new_frenet_frame = ref_path_changed
                plan.reversing = tick_count#mconfig.mkey == Maneuver.M_REVERSE
...

GeoScenario Config

Test

Results

...
|VID:   4|Jump Back Count:  21|Max Jump Back Dist:  2.604170|Plan Change Count:  21|Min Tick Diff:   2|
|VID:   3|Jump Back Count:  15|Max Jump Back Dist:  2.308087|Plan Change Count:  15|Min Tick Diff:   3|
|VID:   5|Jump Back Count:  25|Max Jump Back Dist:  2.773198|Plan Change Count:  25|Min Tick Diff:   3|
|VID:  10|Jump Back Count:  25|Max Jump Back Dist:  2.429843|Plan Change Count:  25|Min Tick Diff:   3|
|VID:   9|Jump Back Count:  22|Max Jump Back Dist:  1.888675|Plan Change Count:  22|Min Tick Diff:   2|
|VID:   8|Jump Back Count:  11|Max Jump Back Dist:  0.924934|Plan Change Count:  11|Min Tick Diff:   3|
|VID:   7|Jump Back Count:  10|Max Jump Back Dist:  0.932807|Plan Change Count:  10|Min Tick Diff:   2|
|VID:   6|Jump Back Count:   7|Max Jump Back Dist:  0.302368|Plan Change Count:   7|Min Tick Diff:   3|
|VID:   2|Jump Back Count:  14|Max Jump Back Dist:  1.359995|Plan Change Count:  14|Min Tick Diff:   2|
|VID:   1|Jump Back Count:  16|Max Jump Back Dist:  0.966820|Plan Change Count:  16|Min Tick Diff:   2|
TICK_COUNT: 996
...
mantkiew commented 3 years ago

It is clear that planning of the new trajectory should start from the projected position of the agent along the old trajectory. Let's ignore the high-frequency planner idea for now as there is no slipping and other physical effects here that would warrant it. Because we know how long planning takes (we can measure that and use for the projection for the next planning cycle), we can pretty precisely project the agents position along the old trajectory.