Flatland
Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
flatland_server::World Class Reference

#include <world.h>

Inheritance diagram for flatland_server::World:
Inheritance graph
[legend]
Collaboration diagram for flatland_server::World:
Collaboration graph
[legend]

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 WorldMakeWorld (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.
 

Detailed Description

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.

Member Function Documentation

void flatland_server::World::BeginContact ( b2Contact *  contact)
override

Box2D inherited begin contact.

Parameters
[in]contactBox2D contact information
void flatland_server::World::DebugVisualize ( bool  update_layers = true)

Publish debug visualizations for everything.

Parameters
[in]update_layerssince 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

Parameters
[in]nameThe name of the model to remove
void flatland_server::World::EndContact ( b2Contact *  contact)
override

Box2D inherited end contact.

Parameters
[in]contactBox2D contact information
void flatland_server::World::LoadLayers ( YamlReader layers_reader)

load layers into the world. Throws YAMLException.

Parameters
[in]layers_readerYaml 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.

Parameters
[in]model_yaml_pathRelative path to the model yaml file
[in]nsNamespace of the robot
[in]nameName of the model
[in]poseInitial pose of the model in x, y, yaw
void flatland_server::World::LoadModels ( YamlReader models_reader)

load models into the world. Throws YAMLException.

Parameters
[in]layers_readerYaml reader for node that has a list of models
World * flatland_server::World::MakeWorld ( const std::string &  yaml_path)
static

factory method to create a instance of the world class. Cleans all the inputs before instantiation of the class. TThrows YAMLException.

Parameters
[in]yaml_pathPath to the world yaml file
Returns
pointer to a new world
void flatland_server::World::MoveModel ( const std::string &  name,
const Pose pose 
)

move model with a given name

Parameters
[in]nameThe name of the model to move
[in]poseThe desired new pose of the model
void flatland_server::World::PostSolve ( b2Contact *  contact,
const b2ContactImpulse *  impulse 
)

Box2D inherited pre solve.

Parameters
[in]contactBox2D contact information
[in]impulseThe calculated impulse from the collision resolute
void flatland_server::World::PreSolve ( b2Contact *  contact,
const b2Manifold *  oldManifold 
)

Box2D inherited presolve.

Parameters
[in]contactBox2D contact information
[in]oldManifoldThe manifold from the previous timestep
void flatland_server::World::Update ( Timekeeper timekeeper)

trigger world update include all physics and plugins

Parameters
[in]timekeeperThe time keeping object

Member Data Documentation

bool flatland_server::World::service_paused_

indicates if simulation is paused by a service call or not


The documentation for this class was generated from the following files: