📄 using.html
字号:
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN"><html><head><meta http-equiv="Content-Type" content="text/html;charset=UTF-8"><title>RVO: Using the RVO Library</title><link href="doxygen.css" rel="stylesheet" type="text/css"><link href="tabs.css" rel="stylesheet" type="text/css"></head><body><!-- Generated by Doxygen 1.5.5 --><div class="navigation" id="top"> <div class="tabs"> <ul> <li><a href="index.html"><span>Main Page</span></a></li> <li><a href="annotated.html"><span>Classes</span></a></li> <li><a href="files.html"><span>Files</span></a></li> </ul> </div> <div class="navpath"><a class="el" href="index.html">RVO Library Documentation</a> </div></div><div class="contents"><h1><a class="anchor" name="using">Using the RVO Library </a></h1>In this section we describe how the RVO library can be used in your software to simulate agents.<h2><a class="anchor" name="rvostructure">Structure</a></h2>A program performing an RVO simulation has the following global structure.<p><div class="fragment"><pre class="fragment"><span class="preprocessor">#include "<a class="code" href="_r_v_o_simulator_8h.html">RVOSimulator.h</a>"</span><span class="keywordtype">int</span> main() { <span class="comment">// Create a simulator instance </span> <a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html">RVO::RVOSimulator</a> * sim = <a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#550565f8b1abe1c258abefe9cf6ae615">RVO::RVOSimulator::Instance</a>(); <span class="comment">// Set up the scenario</span> setupScenario( sim ); <span class="comment">// Initialize the simulation</span> sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#4db589555c45186b6ac1c50f94c4cd95">initSimulation</a>(); <span class="comment">// Perform (and manipulate) the simulation</span> <span class="keywordflow">do</span> { updateVisualization( sim ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#1bf620a40a55daa9207cfbb3a1feea5c">doStep</a>(); } <span class="keywordflow">while</span> ( !sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#e6feb9aeb0acd4a6b773b80d928cdd89">getReachedGoal</a>() ); <span class="keyword">delete</span> sim;}</pre></div><p>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 <a class="el" href="class_r_v_o_1_1_r_v_o_simulator.html#4db589555c45186b6ac1c50f94c4cd95">RVO::RVOSimulator::initSimulation()</a>. 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 <a class="el" href="class_r_v_o_1_1_r_v_o_simulator.html#1bf620a40a55daa9207cfbb3a1feea5c">RVO::RVOSimulator::doStep()</a> 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.<h2><a class="anchor" name="spec">Setting up the Simulation Scenario</a></h2>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.<p><div class="fragment"><pre class="fragment"><span class="keywordtype">void</span> setupScenario( <a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html">RVO::RVOSimulator</a> * sim ) { <span class="comment">// Specify global time step of the simulation</span> sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#8f17c944e96b256d1a5e731817fc7f75">setTimeStep</a>( 0.25f ); <span class="comment">// Specify default parameters for agents that are subsequently added</span> sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#2b19ac57ed6a453d81c9513dcd2d2cda">setAgentDefaults</a>( 250, 15.0f, 10, 2.0f, 3.0f, 1.0f, 2.0f, 7.5f, 1.0f ); <span class="comment">// Add agents (and simulataneously their goals), specifying their start position and goal ID</span> sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#592047a35ba07d8701f0a5216fc62d5a">addAgent</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(-50.0f, -50.0f), sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#4fd87e0d0b4abc44b0453686bea4c970">addGoal</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(50.0f, 50.0f) ) ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#592047a35ba07d8701f0a5216fc62d5a">addAgent</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(50.0f, -50.0f), sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#4fd87e0d0b4abc44b0453686bea4c970">addGoal</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(-50.0f, 50.0f) ) ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#592047a35ba07d8701f0a5216fc62d5a">addAgent</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(50.0f, 50.0f), sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#4fd87e0d0b4abc44b0453686bea4c970">addGoal</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(-50.0f, -50.0f) ) ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#592047a35ba07d8701f0a5216fc62d5a">addAgent</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(-50.0f, 50.0f), sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#4fd87e0d0b4abc44b0453686bea4c970">addGoal</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(50.0f, -50.0f) ) ); <span class="comment">// Add (line segment) obstacles, specifying both endpoints of the line segments</span> sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#90a0a8fa67ec4b08e1befaf376362d53">addObstacle</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(-7.0f, -20.0f), <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(-7.0f, 20.0f) ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#90a0a8fa67ec4b08e1befaf376362d53">addObstacle</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(-7.0f, 20.0f), <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(7.0f, 20.0f) ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#90a0a8fa67ec4b08e1befaf376362d53">addObstacle</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(7.0f, 20.0f), <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(7.0f, -20.0f) ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#90a0a8fa67ec4b08e1befaf376362d53">addObstacle</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(7.0f, -20.0f), <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(-7.0f, -20.0f) ); <span class="comment">// Add roadmap vertices, specifying their position</span> sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#821b8c6f524c7eda2f54f81ba225a467">addRoadmapVertex</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(-10.0f, -23.0f) ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#821b8c6f524c7eda2f54f81ba225a467">addRoadmapVertex</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(-10.0f, 23.0f) ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#821b8c6f524c7eda2f54f81ba225a467">addRoadmapVertex</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(10.0f, 23.0f) ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#821b8c6f524c7eda2f54f81ba225a467">addRoadmapVertex</a>( <a class="code" href="class_r_v_o_1_1_vector2.html">RVO::Vector2</a>(10.0f, -23.0f) ); <span class="comment">// Do not automatically create edges between mutually visible roadmap vertices</span> sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#ed6d7b2d27b469e61deb6ecb7c6fae60">setRoadmapAutomatic</a>( <span class="keyword">false</span> ); <span class="comment">// Manually specify edges between vertices, specifying the ID's of the vertices the edges connect</span> sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#a00529f80bf422bc5a12844399993cf7">addRoadmapEdge</a>( 0, 1 ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#a00529f80bf422bc5a12844399993cf7">addRoadmapEdge</a>( 1, 2 ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#a00529f80bf422bc5a12844399993cf7">addRoadmapEdge</a>( 2, 3 ); sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#a00529f80bf422bc5a12844399993cf7">addRoadmapEdge</a>( 3, 0 );}</pre></div><p>See the documentation on <a class="el" href="class_r_v_o_1_1_r_v_o_simulator.html">RVO::RVOSimulator</a> for a full overview of the functionality to specify scenarios.<h2><a class="anchor" name="ret">Retrieving Information from the Simulation</a></h2>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.<p><div class="fragment"><pre class="fragment"><span class="keywordtype">void</span> updateVisualization( <a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html">RVO::RVOSimulator</a> * sim ) { <span class="comment">// Output the current global time</span> std::cout << sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#ba7c0330e2e539a58fec59d5d40d2ade">getGlobalTime</a>() << <span class="stringliteral">" "</span>; <span class="comment">// Output the position and orientation for all the agents</span> <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = 0; i < sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#fd894bc49201cdd5b9b4678a7990d257">getNumAgents</a>(); ++i) { std::cout << sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#0091c8d48bbc4d31e9c0ec2b0b9daa12">getAgentPosition</a>( i ) << <span class="stringliteral">" "</span> << sim-><a class="code" href="class_r_v_o_1_1_r_v_o_simulator.html#e42c0e05286494cef59150f3d9d3fc8b">getAgentOrientation</a>( i ) << <span class="stringliteral">" "</span>; } std::cout << std::endl;}</pre></div><p>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 <a class="el" href="class_r_v_o_1_1_r_v_o_simulator.html">RVO::RVOSimulator</a> for an exhaustive list of public functions for retrieving simulation information.<h2><a class="anchor" name="manip">Manipulating the Simulation</a></h2>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 <a class="el" href="class_r_v_o_1_1_r_v_o_simulator.html">RVO::RVOSimulator</a> for an exhaustive list of public functions for manipulating the simulation.<p>It is not allowed to add goals, agents, obstacles or roadmap vertices to the simulation, after the simulation has been initialized by calling <a class="el" href="class_r_v_o_1_1_r_v_o_simulator.html#4db589555c45186b6ac1c50f94c4cd95">RVO::RVOSimulator::initSimulation()</a>. Also, it is impossible to change the position of the goals, obstacles or the roadmap vertices. </div><hr size="1"><address style="text-align: right;"><small>Generated on Sun May 25 17:16:13 2008 for RVO by <a href="http://www.doxygen.org/index.html"><img src="doxygen.png" alt="doxygen" align="middle" border="0"></a> 1.5.5 </small></address></body></html>
⌨️ 快捷键说明
复制代码
Ctrl + C
搜索代码
Ctrl + F
全屏模式
F11
切换主题
Ctrl + Shift + D
显示快捷键
?
增大字号
Ctrl + =
减小字号
Ctrl + -