|
Flatland
|
#include <world.h>


Public Member Functions | |
| World () | |
| Constructor for the world class. All data required for initialization should be passed in here. | |
| ~World () | |
| Destructor for the world class. | |
| void | Update (Timekeeper &timekeeper) |
| trigger world update include all physics and plugins More... | |
| void | BeginContact (b2Contact *contact) override |
| Box2D inherited begin contact. More... | |
| void | EndContact (b2Contact *contact) override |
| Box2D inherited end contact. More... | |
| void | PreSolve (b2Contact *contact, const b2Manifold *oldManifold) |
| Box2D inherited presolve. More... | |
| void | PostSolve (b2Contact *contact, const b2ContactImpulse *impulse) |
| Box2D inherited pre solve. More... | |
| void | LoadWorldPlugins (YamlReader &world_plugin_reader, World *world, YamlReader &world_config) |
| void | LoadLayers (YamlReader &layers_reader) |
| load layers into the world. Throws YAMLException. More... | |
| void | LoadModels (YamlReader &models_reader) |
| load models into the world. Throws YAMLException. More... | |
| void | LoadModel (const std::string &model_yaml_path, const std::string &ns, const std::string &name, const Pose &pose) |
| load models into the world. Throws YAMLException. More... | |
| void | DeleteModel (const std::string &name) |
| remove model with a given name More... | |
| void | MoveModel (const std::string &name, const Pose &pose) |
| move model with a given name More... | |
| void | Pause () |
| set the paused state of the simulation to true | |
| void | Resume () |
| set the paused state of the simulation to false | |
| void | TogglePaused () |
| toggle the paused state of the simulation | |
| bool | IsPaused () |
| returns true if service_paused_ is true or an interactive marker is currently being dragged | |
| void | DebugVisualize (bool update_layers=true) |
| Publish debug visualizations for everything. More... | |
Static Public Member Functions | |
| static World * | MakeWorld (const std::string &yaml_path) |
| factory method to create a instance of the world class. Cleans all the inputs before instantiation of the class. TThrows YAMLException. More... | |
Public Attributes | |
| boost::filesystem::path | world_yaml_dir_ |
| directory containing world file | |
| b2World * | physics_world_ |
| Box2D physics world. | |
| b2Vec2 | gravity_ |
| Box2D world gravity, always (0, 0) | |
| std::map< std::vector< std::string >, Layer * > | layers_name_map_ |
| map of all layers and thier name | |
| std::vector< Layer * > | layers_ |
| list of layers | |
| std::vector< Model * > | models_ |
| list of models | |
| CollisionFilterRegistry | cfr_ |
| collision registry for layers and models | |
| PluginManager | plugin_manager_ |
| for loading and updating plugins | |
| bool | service_paused_ |
| InteractiveMarkerManager | int_marker_manager_ |
| for dynamically moving models from Rviz | |
| int | physics_position_iterations_ |
| Box2D solver param. | |
| int | physics_velocity_iterations_ |
| Box2D solver param. | |
This class defines a world in the simulation. A world contains layers that can represent environments at multiple levels, and models which are can be robots or obstacles.
|
override |
Box2D inherited begin contact.
| [in] | contact | Box2D contact information |
| void flatland_server::World::DebugVisualize | ( | bool | update_layers = true | ) |
Publish debug visualizations for everything.
| [in] | update_layers | since layers are pretty much static, this parameter is used to skip updating layers |
| void flatland_server::World::DeleteModel | ( | const std::string & | name | ) |
remove model with a given name
| [in] | name | The name of the model to remove |
|
override |
Box2D inherited end contact.
| [in] | contact | Box2D contact information |
| void flatland_server::World::LoadLayers | ( | YamlReader & | layers_reader | ) |
load layers into the world. Throws YAMLException.
| [in] | layers_reader | Yaml reader for node that has list of layers |
| void flatland_server::World::LoadModel | ( | const std::string & | model_yaml_path, |
| const std::string & | ns, | ||
| const std::string & | name, | ||
| const Pose & | pose | ||
| ) |
load models into the world. Throws YAMLException.
| [in] | model_yaml_path | Relative path to the model yaml file |
| [in] | ns | Namespace of the robot |
| [in] | name | Name of the model |
| [in] | pose | Initial pose of the model in x, y, yaw |
| void flatland_server::World::LoadModels | ( | YamlReader & | models_reader | ) |
load models into the world. Throws YAMLException.
| [in] | layers_reader | Yaml reader for node that has a list of models |
|
static |
factory method to create a instance of the world class. Cleans all the inputs before instantiation of the class. TThrows YAMLException.
| [in] | yaml_path | Path to the world yaml file |
| void flatland_server::World::MoveModel | ( | const std::string & | name, |
| const Pose & | pose | ||
| ) |
move model with a given name
| [in] | name | The name of the model to move |
| [in] | pose | The desired new pose of the model |
| void flatland_server::World::PostSolve | ( | b2Contact * | contact, |
| const b2ContactImpulse * | impulse | ||
| ) |
Box2D inherited pre solve.
| [in] | contact | Box2D contact information |
| [in] | impulse | The calculated impulse from the collision resolute |
| void flatland_server::World::PreSolve | ( | b2Contact * | contact, |
| const b2Manifold * | oldManifold | ||
| ) |
Box2D inherited presolve.
| [in] | contact | Box2D contact information |
| [in] | oldManifold | The manifold from the previous timestep |
| void flatland_server::World::Update | ( | Timekeeper & | timekeeper | ) |
trigger world update include all physics and plugins
| [in] | timekeeper | The time keeping object |
| bool flatland_server::World::service_paused_ |
indicates if simulation is paused by a service call or not
1.8.11