MengeCrowdSim / Menge

The source code for the Menge crowd simulation framework
Apache License 2.0
138 stars 64 forks source link

Simulation does not finish (except for maximum time limit). #84

Closed HendrikBV closed 6 years ago

HendrikBV commented 6 years ago

I'm trying to model groups of people traveling from one room in the building to another room in the building (more precisely, at a university when switching rooms between consecutive lectures, I want to model the flows of all traveling students).

I have a goal in each room of the building (a point) and each agent group starts in a state where they want to travel towards that goal. I also have a final "stop" state to indicate when an agent has reached his or her destination. However, to avoid agents blocking the doors of the rooms for other pedestrians I teleport them away to a location further away, see xml excerpt below.

image

image

What I then want to do is record the time it takes for the last agent to reach his or her destination. The simulation time limit is set to 1800 seconds. However, sometimes the simulation does not finish, i.e. some agents never seem to reach their destinations. When this happens, I try the calculations again. The weird thing is that sometimes it does finish and then with e.g. 300 seconds travel time. (Now, I know that the results are stochastic and thus can differ between runs because agent's preferred free walking speed is drawn from a normal distribution.)

For the PedVO model, I have been able to reproduce the issue with visualization.

image

Pedestrians seem to block the hallway. Moreover, some pedestrians get stuck behind the wall of the adjacent room. After that, they are stuck and can't seem to find the way back towards their goal? I'm using a road map. I guess they take the nearest node (opposite the wall) instead of the nearest feasible node (inside the room)?

I have tried the other pedestrian models as well and sometimes they seem to work for the same specific problem data, only to fail for other problem data.

I'm wondering whether this issue is because I set the goals, states and transitions wrongly or if this is simply due to the large number of people that travel through relatively narrow hallways? Moreover, is there any solution I can implement to avoid this problem?

Another problem that I have seen with the social-force models is that after teleportation when the agents are in their final state they are still moving, so that the simulation does not finish. However, they should be in their final state, so I don't understand how this works.

Thanks in advance.

curds01 commented 6 years ago

As I read your snippet, it should be the case that a final simulation is "empty" (i.e., all agents have been teleported off to some distant, unvisualized space). Correct? And, if so, the problem is that the agents are not successfully navigating to their goals.

So, this could be related to the definition of the goals and could be related to the definition of the roadmap (or some combination of both). The best thing you could do is give me access to the full simulation specification and I can take a look at it.

HendrikBV commented 6 years ago

That is correct. Here are the specifications for which the problem occurs.

behavior.txt scene.txt view.txt Road_Map_KUL.txt

curds01 commented 6 years ago

As I look at your data, your problem most likely stems from your definition of obstacles. Menge works best with closed polygons. I note that your obstacles are defined as a concatenation of line segments. (I.e., a whole bunch of 2-vertex obstacles). Menge's reasoning includes looking around corners. However, when you have two convex obstacles which are different obstacles, but coincident at end points, Menge can't look around corners. It has no knowledge that the two walls are connected. You'll note in the office example that all of the walls have "thickness" ; there are no interior walls that are simply line segments.

Given the complexity of the environment you've created, correcting the obstacle definition might be problematic. At, the very least, it'll be painful to re define each floor to have walls with thickness. So, I'll ponder what can be done about this.

HendrikBV commented 6 years ago

Thank you for your response.

I have changed the definition of the obstacles so that all walls have thickness and that all walls that are connected are defined as a single obstacle. I have attached the new scene specification below.

scene_new.txt

However, the same problem occurs. Here you see that some agents are pushed back into the room and they get stuck behind the obstacle.

image

Here the agent wants to reach the vertex of the road map opposite the wall, but does not know that (s)he should go around the corner.

image

Perhaps my redefinition of obstacles is still wrong?

curds01 commented 6 years ago

I'm inclined to think there is probably a bug in the roadmap following code.

I know that in roadmap following, the agent looks along its path to identify the farthest waypoint it can find and head to it. (You can observe that when you click on an agent.) There's supposed to be some logic that can unwind that; if the waypoint it's heading to is not visible, it backs up to the "last viable" waypoint. However, in this case, it looks like the highlighted agent was moving from the top of the screen to the bottom of the screen. The waypoint at the top was viable, so the agent advanced to a waypoint at the bottom of the screen. However, a cross flow of agents pulled the agent sideways and into the room. In this case, none of the way points on its path are visible. It should replan, but it's not.

Sounds like a bug. And the amount it pops up for you will depend how often agents are swept off of their paths and into cul de sacs. I'll create a simple test to reproduce this and submit an issue for the bug.

curds01 commented 6 years ago

Short term fixes would be to create navigation meshes (which I'm not 100% sure will work with teleportation) or guidance fields (which is incredibly tedious).

So, until I track down this bug, what you'll have to do is run lots of simulations and throw out all of the simulations which time out on simulation duration (instead of the roughly 300 seconds it normally terminates).

curds01 commented 6 years ago

My first test to validate the "waypoint visibility" hypothesis is insufficient.

I created a small scenario in which an agent is swept up by a larger crowd into a space in which none of the path waypoints are visible. The attached image illustrates the scenario as time progresses (and the simulation project is attached below).

Essentially, the key is that the agent remembers the last location it was at when it could see waypoints and that becomes its waypoint. This scenario is insufficient, because heading back to that point is actually possible. It seems in your scenario, the last position at which the path points was visible is no longer directly reachable.

So, tomorrow I'll do another variation of this scenario -- one in which the position waypoints were last visible is no longer reachable after the agent is finished being swept. But I can easily imagine what is wrong with the code -- if the path isn't visible at all, it only remembers the last location it could see the path. In reality, if that position isn't visible, it really needs to replan.

simulation

roadmap_hijack.zip

HendrikBV commented 6 years ago

When I look at the source code, I see that in VelCompRoadMap.cpp the function 'setPrefVelocity()' creates a roadmap for each agent at the start of the simulation and then always uses that roadmap to compute the preferred direction.

void RoadMapVelComponent::setPrefVelocity( const Agents::BaseAgent * agent, const Goal * goal, Agents::PrefVelocity & pVel ) const {
            _lock.lockRead();
            PathMap::const_iterator itr = _paths.find( agent->_id );
            RoadMapPath * path = 0x0;
            if ( itr == _paths.end() ) {
                _lock.releaseRead();
                // compute the path and add it to the map
                //  Create path for the agent
                Vector2 goalPoint = goal->getCentroid();
                path = _roadmap->getPath( agent, goal ); 
                _lock.lockWrite();
                _paths[ agent->_id ] = path;
                _lock.releaseWrite();
            } else {
                path = itr->second;
                _lock.releaseRead();
            }
            pVel.setSpeed( agent->_prefSpeed );
            path->setPrefDirection( agent, pVel );
        }

The computation of the preferred direction is done by the function 'setPrefDirection()' in RoadMapPath.cpp. Now, if I'm correct, what happens is this function checks the visibility of the current targetID (the current target node on the road map) and tries to advance the agent's current target to the farthest node that is still visible.

void RoadMapPath::setPrefDirection( const Agents::BaseAgent * agent, Agents::PrefVelocity & pVel ) {
        // Assume that when I'm overlapping one node, that I can see the next
        // Test to see if I can advance target way point
        //  while I'm overlapping current target, advance it
        //      assert that it is visible
        //
        // test to see if current target is visible
        //  if visible
        //          direction towards it
        //          current position last valid
        //   else
        //          direction towards last valid position
        // TODO: This has flaws because the ObstacleKDTree is finding segments visible when it
        //  should not.
        bool isVisible = false;
        // TODO: Should I compute this blindly?  Although it is used in potentially three places
        //      mostly, it won't be used.
        Vector2 target = _goal->getTargetPoint( agent->_pos, agent->_radius );
        if ( _targetID < _wayPointCount ) {
            isVisible =
                Menge::SPATIAL_QUERY->queryVisibility( agent->_pos, _wayPoints[ _targetID ],
                agent->_radius );
        } else {
            isVisible = Menge::SPATIAL_QUERY->queryVisibility( agent->_pos, target,
                                                               agent->_radius );
        }
        size_t testID = _targetID + 1;
        while ( testID < _wayPointCount &&
                Menge::SPATIAL_QUERY->queryVisibility( agent->_pos, _wayPoints[ testID ],
                agent->_radius ) ) {
            _targetID = testID;
            isVisible = true;
            ++testID;
        }
        if ( _targetID == _wayPointCount - 1 ) {
            if ( Menge::SPATIAL_QUERY->queryVisibility( agent->_pos, target, agent->_radius ) ) {
                ++_targetID;
                isVisible = true;
            }
        }
        // Visibility test
        Vector2 dir;
        if ( isVisible ) {
            Vector2 curr( _targetID < _wayPointCount ? _wayPoints[ _targetID ] : target );
            dir = norm( curr - agent->_pos );
            _validPos = agent->_pos;
            pVel.setTarget( curr );
            pVel.setSingle(dir);
        } else {
            // This should never be the zero vector.
            //  _validPos is set when the current waypoint is visible
            //  this code is only achieved when it is NOT visible
            //  POSSIBLY, something weird could happen where the next waypoint isn't visible, but
            //      that breaks the earlier assertion.
            dir = norm( _validPos - agent->_pos );
            pVel.setTarget( _validPos );
        }
                pVel.setSingle(dir);
    }

The problem occurs at the last visibility test. If none of the nodes checked earlier in the function ('_targetID' and 'testID') was visible, then the function uses '_validPos' which should be the node that was visible when the last path computation was executed. However, if my agent is swept away from target and pushed into the room, this '_validPos' node is no longer visible. In that case, the road map should be calculated again from the current position. I think the following changes to both functions achieve this goal.

bool RoadMapPath::setPrefDirection( const Agents::BaseAgent * agent, Agents::PrefVelocity & pVel ) {
        // Assume that when I'm overlapping one node, that I can see the next
        // Test to see if I can advance target way point
        //  while I'm overlapping current target, advance it
        //      assert that it is visible
        //
        // test to see if current target is visible
        //  if visible
        //          direction towards it
        //          current position last valid
        //   else
        //          direction towards last valid position
        // TODO: This has flaws because the ObstacleKDTree is finding segments visible when it
        //  should not.
        bool isVisible = false;
        // TODO: Should I compute this blindly?  Although it is used in potentially three places
        //      mostly, it won't be used.
        Vector2 target = _goal->getTargetPoint( agent->_pos, agent->_radius );
        if ( _targetID < _wayPointCount ) {
            isVisible =
                Menge::SPATIAL_QUERY->queryVisibility( agent->_pos, _wayPoints[ _targetID ],
                agent->_radius );
        } else {
            isVisible = Menge::SPATIAL_QUERY->queryVisibility( agent->_pos, target,
                                                               agent->_radius );
        }
        size_t testID = _targetID + 1;
        while ( testID < _wayPointCount &&
                Menge::SPATIAL_QUERY->queryVisibility( agent->_pos, _wayPoints[ testID ],
                agent->_radius ) ) {
            _targetID = testID;
            isVisible = true;
            ++testID;
        }
        if ( _targetID == _wayPointCount - 1 ) {
            if ( Menge::SPATIAL_QUERY->queryVisibility( agent->_pos, target, agent->_radius ) ) {
                ++_targetID;
                isVisible = true;
            }
        }
        // Visibility test
        Vector2 dir;
        if ( isVisible ) {
            Vector2 curr( _targetID < _wayPointCount ? _wayPoints[ _targetID ] : target );
            dir = norm( curr - agent->_pos );
            _validPos = agent->_pos;
            pVel.setTarget( curr );
            pVel.setSingle(dir);
            return true;
        } else {
            // CHANGED: no visible node was found, so return false
            return false;
        }
    }

Here we make the function RoadMapPath::setPrefDirection() return a bool that indicates whether a visible node has been found. Then in the function RoadMapVelComponent::setPrefVelocity, we calculate a new path for the agent if no visible node was found.

void RoadMapVelComponent::setPrefVelocity( const Agents::BaseAgent * agent, const Goal * goal, Agents::PrefVelocity & pVel ) const {
            _lock.lockRead();
            PathMap::const_iterator itr = _paths.find( agent->_id );
            RoadMapPath * path = 0x0;
            if ( itr == _paths.end() ) {
                _lock.releaseRead();
                // compute the path and add it to the map
                //  Create path for the agent
                Vector2 goalPoint = goal->getCentroid();
                path = _roadmap->getPath( agent, goal ); 
                _lock.lockWrite();
                _paths[ agent->_id ] = path;
                _lock.releaseWrite();
            } else {
                path = itr->second;
                _lock.releaseRead();
            }
            pVel.setSpeed( agent->_prefSpeed );
            bool ok = path->setPrefDirection( agent, pVel );
            if (!ok) {
                // compute the path and add it to the map
                //  Create path for the agent
                Vector2 goalPoint = goal->getCentroid();
                path = _roadmap->getPath(agent, goal);
                _lock.lockWrite();
                _paths[agent->_id] = path;
                _lock.releaseWrite();

                pVel.setSpeed(agent->_prefSpeed);
                ok = path->setPrefDirection(agent, pVel);
            }
        }

If I run the simulation with these changes, no more agents get stuck, so it seems to work.

image

What do you think?

HendrikBV commented 6 years ago

For different simulation scenarios in the same building geometry (different agent groups with different goals) the simulation now always finishes successfully.

image

curds01 commented 6 years ago

You've essentially captured the fix. There are a couple of small details I'm planning on doing differently (related to memory management, synchronization, and replanning frequency) but that's the basic shape. This evening, I'll PR my fix and ping you on it. Then I'll merge it and you can just update from master.