Flatland
Public Member Functions | Public Attributes | List of all members
flatland_plugins::ModelTfPublisher Class Reference

#include <model_tf_publisher.h>

Inheritance diagram for flatland_plugins::ModelTfPublisher:
Inheritance graph
[legend]
Collaboration diagram for flatland_plugins::ModelTfPublisher:
Collaboration graph
[legend]

Public Member Functions

void OnInitialize (const YAML::Node &config) override
 Initialization for the plugin. More...
 
void BeforePhysicsStep (const Timekeeper &timekeeper) override
 Called when just before physics update. More...
 
- Public Member Functions inherited from flatland_server::ModelPlugin
ModelGetModel ()
 Get model.
 
void Initialize (const std::string &type, const std::string &name, Model *model, const YAML::Node &config)
 The method to initialize the ModelPlugin, required since Pluginlib require the class to have a default constructor. More...
 
bool FilterContact (b2Contact *contact, Entity *&entity, b2Fixture *&this_fixture, b2Fixture *&other_fixture)
 Helper function check if this model is part of the contact, and extracts all the useful information. More...
 
bool FilterContact (b2Contact *contact)
 Helper function check if this model is part of the contact. More...
 
- Public Member Functions inherited from flatland_server::FlatlandPlugin
const PluginType Type ()
 
const std::string & GetName () const
 Get plugin name.
 
const std::string & GetType () const
 Get type of plugin.
 
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 world_frame_id_
 name of the world frame id
 
bool publish_tf_world_
 if to publish the world position of the bodies
 
std::vector< Body * > excluded_bodies_
 list of bodies to ignore
 
Bodyreference_body_
 body used as a reference to other bodies
 
double update_rate_
 publish rate
 
tf::TransformBroadcaster tf_broadcaster
 For publish ROS TF.
 
UpdateTimer update_timer_
 for managing update rate
 
- Public Attributes inherited from flatland_server::ModelPlugin
ros::NodeHandle nh_
 ROS node handle.
 
- Public Attributes inherited from flatland_server::FlatlandPlugin
std::string type_
 type of the plugin
 
std::string name_
 name of the plugin
 
ros::NodeHandle nh_
 
PluginType plugin_type_
 

Additional Inherited Members

- Public Types inherited from flatland_server::FlatlandPlugin
enum  PluginType { Invalid, Model, World }
 
- Protected Member Functions inherited from flatland_server::ModelPlugin
 ModelPlugin ()=default
 Model plugin default constructor.
 

Detailed Description

This class implements the model plugin and provides the functionality of publishing ROS TF transformations for the bodies inside a model

Member Function Documentation

void flatland_plugins::ModelTfPublisher::BeforePhysicsStep ( const Timekeeper timekeeper)
overridevirtual

Called when just before physics update.

Parameters
[in]timekeeperObject managing the simulation time

< for storing TF from world to the ref. body

< for storing TF from ref. body to other bodies

Reimplemented from flatland_server::FlatlandPlugin.

void flatland_plugins::ModelTfPublisher::OnInitialize ( const YAML::Node &  config)
overridevirtual

Initialization for the plugin.

Parameters
[in]configPlugin YAML Node

Implements flatland_server::FlatlandPlugin.


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