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

#include <model.h>

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

Public Member Functions

 Model (b2World *physics_world, CollisionFilterRegistry *cfr, const std::string &ns, const std::string &name)
 Constructor for the model. More...
 
 ~Model ()
 Destructor for the layer class.
 
EntityType Type () const
 Return the type of entity. More...
 
void LoadBodies (YamlReader &bodies_reader)
 load bodies to this model, throws exceptions upon failure More...
 
void LoadJoints (YamlReader &joints_reader)
 load joints to this model, throws exceptions upon failure More...
 
ModelBodyGetBody (const std::string &name)
 Get a body in the model using its name. More...
 
JointGetJoint (const std::string &name)
 Get a body in the model using its name. More...
 
const std::vector< ModelBody * > & GetBodies ()
 
const std::vector< Joint * > & GetJoints ()
 
const std::string & GetNameSpace () const
 
std::string NameSpaceTF (const std::string &frame_id) const
 
std::string NameSpaceTopic (const std::string &topic) const
 
const std::string & GetName () const
 
const CollisionFilterRegistryGetCfr () const
 
void DebugVisualize () const override
 Publish debug visualizations for model.
 
void DebugOutput () const override
 log debug messages for the layer
 
void DumpBox2D () const
 Dump box2d data for debugging.
 
void TransformAll (const Pose &pose_delta)
 transform all bodies in the model More...
 
void SetPose (const Pose &pose)
 Explicitly set the model pose in world coordinates. More...
 
- Public Member Functions inherited from flatland_server::Entity
 Entity (b2World *physics_world, const std::string &name)
 Constructor for the entity. More...
 
const std::string & GetName () const
 
b2World * GetPhysicsWorld ()
 Get Box2D physics world. More...
 
 Entity (const Entity &)=delete
 
Entityoperator= (const Entity &)=delete
 

Static Public Member Functions

static ModelMakeModel (b2World *physics_world, CollisionFilterRegistry *cfr, const std::string &model_yaml_path, const std::string &ns, const std::string &name)
 Create a model, throws exceptions upon failure. More...
 

Public Attributes

std::string namespace_
 namespace of the model
 
std::vector< ModelBody * > bodies_
 list of bodies in the model
 
std::vector< Joint * > joints_
 list of joints in the model
 
YamlReader plugins_reader_
 for storing plugins when paring YAML
 
CollisionFilterRegistrycfr_
 Collision filter registry.
 
std::string viz_name_
 used for visualization
 
- Public Attributes inherited from flatland_server::Entity
b2World * physics_world_
 Box2D physics world.
 
std::string name_
 name of the entity
 

Additional Inherited Members

- Public Types inherited from flatland_server::Entity
enum  EntityType { LAYER, MODEL }
 Defines the type of entity.
 

Detailed Description

This class defines a Model. It can be used to repsent any object in the environment such robots, chairs, deskes etc.

Constructor & Destructor Documentation

flatland_server::Model::Model ( b2World *  physics_world,
CollisionFilterRegistry cfr,
const std::string &  ns,
const std::string &  name 
)

Constructor for the model.

Parameters
[in]physics_worldBox2D physics world
[in]cfrCollision filter registry
[in]nameName of the model

Member Function Documentation

const std::vector< ModelBody * > & flatland_server::Model::GetBodies ( )
Returns
List of bodies the model has
ModelBody * flatland_server::Model::GetBody ( const std::string &  name)

Get a body in the model using its name.

Parameters
[in]nameName of the body
Returns
pointer to the body, nullptr indicates body cannot be found
const CollisionFilterRegistry * flatland_server::Model::GetCfr ( ) const
Returns
The collision filter registrar
Joint * flatland_server::Model::GetJoint ( const std::string &  name)

Get a body in the model using its name.

Parameters
[in]nameName of the joint
Returns
pointer to the joint, nullptr if the joint does not exist
const std::vector< Joint * > & flatland_server::Model::GetJoints ( )
Returns
List of joints the model has
const std::string & flatland_server::Model::GetName ( ) const
Returns
The name of the model
const std::string & flatland_server::Model::GetNameSpace ( ) const
Returns
The namespace of the model
void flatland_server::Model::LoadBodies ( YamlReader bodies_reader)

load bodies to this model, throws exceptions upon failure

Parameters
[in]bodies_readerYAML reader for node containing the list of bodies
void flatland_server::Model::LoadJoints ( YamlReader joints_reader)

load joints to this model, throws exceptions upon failure

Parameters
[in]joints_readerYAML reader for node containing the list of joints
Model * flatland_server::Model::MakeModel ( b2World *  physics_world,
CollisionFilterRegistry cfr,
const std::string &  model_yaml_path,
const std::string &  ns,
const std::string &  name 
)
static

Create a model, throws exceptions upon failure.

Parameters
[in]physics_worldBox2D physics world
[in]cfrCollision filter registry
[in]model_yaml_pathAbsolute path to the model yaml file
[in]nsNamespace of the robot
[in]nameName of the model
Returns
A new model
std::string flatland_server::Model::NameSpaceTF ( const std::string &  frame_id) const
Returns
prepend the tf with namespace_
std::string flatland_server::Model::NameSpaceTopic ( const std::string &  topic) const
Returns
prepend the topic with namespace/
void flatland_server::Model::SetPose ( const Pose pose)

Explicitly set the model pose in world coordinates.

Parameters
[in]poseworld x, world y, world yaw
void flatland_server::Model::TransformAll ( const Pose pose_delta)

transform all bodies in the model

Parameters
[in]pose_deltadx, dy, dyaw
EntityType flatland_server::Model::Type ( ) const
inlinevirtual

Return the type of entity.

Returns
Model type

Implements flatland_server::Entity.


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