Menge
Modular Pedestrian Simulation Framework for Research and Development
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Implementing new Pedestrian Models

Overview

The Menge architectural philosophy limits the type of pedestrian models which can be easily implemented as plug-ins. Menge works with a particular class of pedestrian models, those that can be thought of as a function which map a per-agent preferred velocity and local state (nearby obstacles and agents) into a feasible velocity. While this abstraction doesn't include all viable pedestrian simulators, it is a very common and convenient abstraction. This type of pedestrian model is also referred to as a local collision avoidance or local navigation algorithm.

In order to introduce a new pedestrian model into the Menge system, there are certain classes which must be implemented and some which are optional, they include:

The Simulator and Pedestrian classes are responsible for the run-time computation which maps the preferred velocity to a feasible velocity. The Simulator class holds the global simulation parameters. The Pedestrian class holds the per-agent simulation parameters and performs the actual computation.

The Simulator database entry class is how the plug-in registers the new pedestrian model with Menge (see Extending the Simulator). Menge uses it to instantiate the model-specific features at run time. The agent initializer is only required if there are per-agent parameter values (beyond the BaseAgent properties enumerated in the <Common> tag. Finally, you can extend the BaseAgentContext to provide an interactive visualization of the agent's velocity computation. If you do not explicitly define one, the new pedestrian model will use the BaseAgentContext which allows for interactive querying of basic agent properties.

The Pedestrian Model

This section discusses the required elements (including the quasi-optional agent initializer). These must be implemented in order for the model to be usable by Menge. We recommend that you place all of your pedestrian model elements in a common namespace.

Pedestrian Simulator

The Simulator class is responsible for evolving the agent simulator state. It handles nearest neighbor queries, calls the Pedestrians function for computing a feasible velocity, performs the time integration, and maintains the global simulation parameters. Of those duties almost all of them happen automatically and it is unnecessary for you to take any action or even concern yourself with them in implementing a new model. The only task you must concern yourself with is handling your particular model's global parameters.

Your Simulator class should sub-class the templated PedSim::SimulatorBase class. The base class is templated on agent type, so your simulator declaration would look something like this (assuming that your Agent and Simulator are both defined in the namespace NewModel):

namespace NewModel {
    class Simulator : public PedSim::SimulatorBase< Agent > {
    public:
        /*! Functions */
        friend class Agent;
    };
}   // namespace NewModel

If your agent model has no global parameters, then you should simply implement the function PedSim::SimulatorBase::hasExpTarget like this:

virtual bool hasExpTarget() { return false; }

This informs the XML parser that your model does not expect to see any specific global parameter definitions. If, however, your model does have global parameters, then it is necessary to inform the parser and provide the functionality for handling it.

First, the hasExpTarget function must return true. Second, the following function must be implemented, reporting the name of the property set via the function PedSim::SimulatorBase::isExpTarget:

bool isExpTarget( const std::string & tagName ) { return tagName == "TagName"; }

Replace TagName with a uniquely identifying string that is not Common (as that is reserved for the common properties of all pedestrian models). Finally, your Simulator class must handle parsing the properties by implementing the function PedSim::SimulatorBase::setExpParam:

bool setExpParam( const std::string & paramName, const std::string & value ) throw( PedSim::XMLParamException )

Each attribute of the tag TagName will be passed into this function (as a parameter-value pair of strings). The setExpParam function should test the parameter name, making sure it is expected, and confirm that the value is consistent with expectations. If the parameter is expected and the string value is acceptable, it should return true, otherwise return false.

It is recommended that the global parameters be stored as static members of the simulator. This is a reasonable choice because Menge will only instantiate one Simulator at a time. As global members of the simulator, each agent will have easy access to the global parameters without necessarily increasing the agent's memory footprint.

Pedestrian Model

The Pedestrian class computes the new feasible velocity using the pedestrian model's formulation. It should sub-class the PedSim::BaseAgent class. It is only necessary to create a default constructor, destructor, and implement the PedSim::BaseAgent::computeNewVelocity function.

It is very important to note that the computeNewVelocity function should set the PedSim::BaseAgent::_velNew member and should not set the PedSim::BaseAgent::_vel property directly. The _vel property will be set after applying the acceleration constraints.

Parsing Properties from the XML

If your pedestrian model requires per-agent properties which are not part of the <Common> set, then you will need to implement an intializer class, derived from PedSim::AgentInitializer. The initializer helps parse the model's per-agent properties (as a child tag of the AgentSet tag) and uses it to initialize the properties of the agents. Essentially, when reading an AgentSet tag, the agent initializer reads the particular properties defined in the AgentSet and then, for each agent in the set, assigns it property values based on the definitions.

The agent initializer must implement several functions:

The natural reflex in implementing an agent initializer would be to create numerical primitives to represent agent properties. For example, if your model includes a per-agent property called mass, then you would probably add a member to the agent initializer called _mass and simply set it from the value found in the xml. However, per-agent properties can be set with value distributions (TODO: include reference to discussion of value distributions). It achieves this by using PedMath::FloatGenerator and PedMath::IntGenerator classes as appropriate. This means, the agent initializer should store the _mass value as as PedMath::FloatGenerator. By default, it would be a PedMath::ConstFloatGenerator with the default value. This can be replaced by either a different const, or by a different float generator based on the XML specification.

See PedOrca or PedHelbing for an example in how to implement these functions.

Registering the Pedestrian Model

Pedestrian models are registered with Menge via the templated class SimulatorDBEntry. It is templated on both the simulator and the agent classes. The simulator database entry performs several tasks:

The simulator database also handles instantiate the simulator, but this happens automatically in the SimulatorDBEntry class and you do not need to make any explicit effort in this regard.

These functions are simply implemented and largely consist of returning constant strings or implementing one of the other, supporting classes.

Visualizing the Pedestrian Model's Computation

In interactive mode (i.e., with the OpenGL viewer) you can interactively visualize aspects of the agent's state (by hitting the 'A' key). The BaseAgentContext is responsible for displaying the properties which belong to PedSim::BaseAgent. You can use a sub-class of the BaseAgentContext to include parameters which uniquely belong to you novel pedestrian model. You can even use it to show the computation of the new velocity per-agent. To do so, subclass the templated BaseAgentContext with your agent class as the templated parameter. There are several functions which you should implemente:

Ultimately, for more details, see the provided examples.

Setting up the Project

Pedestrian plug-ins are most easily built if they are included in the current project infrastructure. For a pedestrian model called "BetaModel", the recommended setup is to create a folder in the PedPlugins folder called "PedBeta". All files should be added to this folder.

Windows

These instructions make some assumptions:

Do the following:

NOTE: For windows dlls, which C runtime libraries (CRT) you link against will have a significant impact. You should compile your plug-in against the "Multi-threaded DLL" CRT (or "Multi-threaded Debug DLL" for debug builds).

Linux

Adding the pedestrian model plug-in into the build system is simple.

  1. Edit PedPlugins/CMakeLists.txt by adding the line ADD_SUBDIRECTORY(PedBeta).
  2. Copy a CMakeLists.txt file from one of the example pedestrian plug-ins into PedPlugins/PedBeta.
  3. Edit the following:
    • project( ???Model) –> project(BetaModel)
    • change the file list of all .cpp files in your folder
    • replace the library name in the add_library and target_link_libraries directives to betaPed.

Now, the plug-in will be automatically built and placed in the executable folder.