Using the RVO Library

In this section we describe how the RVO Library can be used in your software to simulate agents.

Structure

A program performing an RVO simulation has the following global structure.

#include "RVOSimulator.h"
int main() {
// Create a simulator instance
// Set up the scenario
setupScenario( sim );
// Initialize the simulation
// Perform (and manipulate) the simulation
do {
updateVisualization( sim );
sim->doStep();
} while ( !sim->getReachedGoal() );
delete sim;
}
Definition: RVOSimulator.h:50
bool getReachedGoal() const
Definition: RVOSimulator.h:156
static RVOSimulator * Instance()

In order to use the RVO simulator, the user needs to include "RVOSimulator.h". The first step then is to create an instance of an RVOSimulator. Then, the process consists of two stages. The first stage is specifying the simulation scenario and its parameters. In the above example progam, this is done in the method setupScenario, which we will discuss below. The second stage is the actual performing of the simulation. To finalize the scenario setup and enter the simulation mode, the simulation has to be initialized by calling RVO::RVOSimulator::initSimulation(). Now, the actual simulation can be performed. In the above example program, simulation steps are taken until all the agents have reached their goals. Note that it is not allowed to call RVO::RVOSimulator::doStep() before initializing the simulation. During the simulation, the user may want to retrieve information from the simulation for instance to visualize the simulation. In the above example program, this is done in the method updateVisualization, which we will discuss below. It is also possible to manipulate the simulation during the simulation, for instance by changing positions, preferred speeds, goals, etc. of the agents.

Setting up the Simulation Scenario

A scenario that is to be simulated can be set up as follows. A scenario consists of four types of objects: goals, agents, obstacles and a roadmap to steer the agents around obstacles. Each of them can be manually specified. The following example creates a scenario with four agents exchanging positions around a rectangular obstacle in the middle.

void setupScenario( RVO::RVOSimulator * sim ) {
// Specify global time step of the simulation
sim->setTimeStep( 0.25f );
// Specify default parameters for agents that are subsequently added
sim->setAgentDefaults( 250, 15.0f, 10, 2.0f, 3.0f, 1.0f, 2.0f, 7.5f, 1.0f );
// Add agents (and simulataneously their goals), specifying their start position and goal ID
sim->addAgent( RVO::Vector2(-50.0f, -50.0f), sim->addGoal( RVO::Vector2(50.0f, 50.0f) ) );
sim->addAgent( RVO::Vector2(50.0f, -50.0f), sim->addGoal( RVO::Vector2(-50.0f, 50.0f) ) );
sim->addAgent( RVO::Vector2(50.0f, 50.0f), sim->addGoal( RVO::Vector2(-50.0f, -50.0f) ) );
sim->addAgent( RVO::Vector2(-50.0f, 50.0f), sim->addGoal( RVO::Vector2(50.0f, -50.0f) ) );
// Add (line segment) obstacles, specifying both endpoints of the line segments
sim->addObstacle( RVO::Vector2(-7.0f, -20.0f), RVO::Vector2(-7.0f, 20.0f) );
sim->addObstacle( RVO::Vector2(-7.0f, 20.0f), RVO::Vector2(7.0f, 20.0f) );
sim->addObstacle( RVO::Vector2(7.0f, 20.0f), RVO::Vector2(7.0f, -20.0f) );
sim->addObstacle( RVO::Vector2(7.0f, -20.0f), RVO::Vector2(-7.0f, -20.0f) );
// Add roadmap vertices, specifying their position
sim->addRoadmapVertex( RVO::Vector2(-10.0f, -23.0f) );
sim->addRoadmapVertex( RVO::Vector2(-10.0f, 23.0f) );
sim->addRoadmapVertex( RVO::Vector2(10.0f, 23.0f) );
sim->addRoadmapVertex( RVO::Vector2(10.0f, -23.0f) );
// Do not automatically create edges between mutually visible roadmap vertices
sim->setRoadmapAutomatic( false );
// Manually specify edges between vertices, specifying the ID's of the vertices the edges connect
sim->addRoadmapEdge( 0, 1 );
sim->addRoadmapEdge( 1, 2 );
sim->addRoadmapEdge( 2, 3 );
sim->addRoadmapEdge( 3, 0 );
}
void setAgentDefaults(int velSampleCountDefault, float neighborDistDefault, int maxNeighborsDefault, float radiusDefault, float goalRadiusDefault, float prefSpeedDefault, float maxSpeedDefault, float safetyFactorDefault, float maxAccelDefault=RVO_INFTY, const Vector2 &velocityDefault=Vector2(0, 0), float orientationDefault=0, int classDefault=0)
int addGoal(const Vector2 &position)
int addAgent(const Vector2 &startPosition, int goalID)
int addRoadmapVertex(const Vector2 &position)
void setTimeStep(float stepSize)
Definition: RVOSimulator.h:170
int addObstacle(const Vector2 &point1, const Vector2 &point2)
int addRoadmapEdge(int vertexID1, int vertexID2)
void setRoadmapAutomatic(bool automatic=true)
Definition: vector2.h:11

See the documentation on RVO::RVOSimulator for a full overview of the functionality to specify scenarios.

Retrieving Information from the Simulation

During the simulation, the user can extract information from the simulation for instance for visualization purposes. In the example program above, this is done in the updateVisualization method. Here we give an example that simply writes the positions and orientations of each agent in each time step to the standard output.

void updateVisualization( RVO::RVOSimulator * sim ) {
// Output the current global time
std::cout << sim->getGlobalTime() << " ";
// Output the position and orientation for all the agents
for (int i = 0; i < sim->getNumAgents(); ++i) {
std::cout << sim->getAgentPosition( i ) << " " << sim->getAgentOrientation( i ) << " ";
}
std::cout << std::endl;
}
int getNumAgents() const
const Vector2 & getAgentPosition(int agentID) const
float getGlobalTime() const
Definition: RVOSimulator.h:160
float getAgentOrientation(int agentID) const

Using similar functions as the ones used in this example, the user can access information about other parameters of the agents, as well as the global parameters, the obstacles and the roadmap. See the documentation of the class RVO::RVOSimulator for an exhaustive list of public functions for retrieving simulation information.

Manipulating the Simulation

During the simulation, the user can manipulate the simulation, for instance by changing the global parameters, or changing the parameters of the agents (causing abrupt different behavior). It is also possible to give the agents a new position, which make them jump through the scene. See the documentation of the class RVO::RVOSimulator for an exhaustive list of public functions for manipulating the simulation.

It is not allowed to add goals, agents, obstacles or roadmap vertices to the simulation, after the simulation has been initialized by calling RVO::RVOSimulator::initSimulation(). Also, it is impossible to change the position of the goals, obstacles or the roadmap vertices.