Flatland
Public Types | Public Member Functions | Public Attributes | List of all members
flatland_server::FlatlandPlugin Class Referenceabstract
Inheritance diagram for flatland_server::FlatlandPlugin:
Inheritance graph
[legend]
Collaboration diagram for flatland_server::FlatlandPlugin:
Collaboration graph
[legend]

Public Types

enum  PluginType { Invalid, Model, World }
 

Public Member Functions

const PluginType Type ()
 
const std::string & GetName () const
 Get plugin name.
 
const std::string & GetType () const
 Get type of plugin.
 
virtual void OnInitialize (const YAML::Node &config)=0
 The method for the particular model plugin to override and provide its own initialization. More...
 
virtual void BeforePhysicsStep (const Timekeeper &timekeeper)
 This method is called before the Box2D physics step. More...
 
virtual void AfterPhysicsStep (const Timekeeper &timekeeper)
 This method is called after the Box2D physics step. More...
 
virtual void BeginContact (b2Contact *contact)
 A method that is called for all Box2D begin contacts. More...
 
virtual void EndContact (b2Contact *contact)
 A method that is called for all Box2D end contacts. More...
 
virtual void PreSolve (b2Contact *contact, const b2Manifold *oldManifold)
 A method that is called for Box2D presolve. More...
 
virtual void PostSolve (b2Contact *contact, const b2ContactImpulse *impulse)
 A method that is called for Box2D postsolve. More...
 
virtual ~FlatlandPlugin ()=default
 Flatland plugin destructor.
 

Public Attributes

std::string type_
 type of the plugin
 
std::string name_
 name of the plugin
 
ros::NodeHandle nh_
 
PluginType plugin_type_
 

Member Function Documentation

virtual void flatland_server::FlatlandPlugin::AfterPhysicsStep ( const Timekeeper timekeeper)
inlinevirtual

This method is called after the Box2D physics step.

Parameters
[in]timekeeperprovide time related information

Reimplemented in flatland_plugins::Bumper, and flatland_plugins::BoolSensor.

virtual void flatland_server::FlatlandPlugin::BeforePhysicsStep ( const Timekeeper timekeeper)
inlinevirtual

This method is called before the Box2D physics step.

Parameters
[in]timekeeperprovide time related information

Reimplemented in flatland_plugins::Laser, flatland_plugins::Tween, flatland_plugins::TricycleDrive, flatland_plugins::Bumper, flatland_plugins::DiffDrive, flatland_plugins::ModelTfPublisher, and flatland_plugins::Gps.

virtual void flatland_server::FlatlandPlugin::BeginContact ( b2Contact *  contact)
inlinevirtual

A method that is called for all Box2D begin contacts.

Parameters
[in]contactBox2D contact

Reimplemented in flatland_plugins::Bumper, and flatland_plugins::BoolSensor.

virtual void flatland_server::FlatlandPlugin::EndContact ( b2Contact *  contact)
inlinevirtual

A method that is called for all Box2D end contacts.

Parameters
[in]contactBox2D contact

Reimplemented in flatland_plugins::Bumper, and flatland_plugins::BoolSensor.

virtual void flatland_server::FlatlandPlugin::OnInitialize ( const YAML::Node &  config)
pure virtual
virtual void flatland_server::FlatlandPlugin::PostSolve ( b2Contact *  contact,
const b2ContactImpulse *  impulse 
)
inlinevirtual

A method that is called for Box2D postsolve.

Parameters
[in]contactBox2D contact
[in]impulseImpulse from the collision resolution

Reimplemented in flatland_plugins::Bumper.

virtual void flatland_server::FlatlandPlugin::PreSolve ( b2Contact *  contact,
const b2Manifold *  oldManifold 
)
inlinevirtual

A method that is called for Box2D presolve.

Parameters
[in]contactBox2D contact
[in]oldManifoldManifold from the previous iteration

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