47 #ifndef FLATLAND_SERVER_FLATLAND_PLUGIN_H 48 #define FLATLAND_SERVER_FLATLAND_PLUGIN_H 50 #include <Box2D/Box2D.h> 51 #include <flatland_server/timekeeper.h> 53 #include <yaml-cpp/yaml.h> 59 enum class PluginType { Invalid,
Model,
World };
63 PluginType plugin_type_;
68 const PluginType Type() {
return plugin_type_; }
116 virtual void PreSolve(b2Contact *contact,
const b2Manifold *oldManifold) {}
123 virtual void PostSolve(b2Contact *contact,
const b2ContactImpulse *impulse) {}
132 #endif // FLATLAND_SERVER_FLATLAND_PLUGIN_H virtual void AfterPhysicsStep(const Timekeeper &timekeeper)
This method is called after the Box2D physics step.
Definition: flatland_plugin.h:97
virtual void PreSolve(b2Contact *contact, const b2Manifold *oldManifold)
A method that is called for Box2D presolve.
Definition: flatland_plugin.h:116
virtual ~FlatlandPlugin()=default
Flatland plugin destructor.
virtual void PostSolve(b2Contact *contact, const b2ContactImpulse *impulse)
A method that is called for Box2D postsolve.
Definition: flatland_plugin.h:123
virtual void BeforePhysicsStep(const Timekeeper &timekeeper)
This method is called before the Box2D physics step.
Definition: flatland_plugin.h:91
const std::string & GetName() const
Get plugin name.
Definition: flatland_plugin.h:73
const std::string & GetType() const
Get type of plugin.
Definition: flatland_plugin.h:78
virtual void BeginContact(b2Contact *contact)
A method that is called for all Box2D begin contacts.
Definition: flatland_plugin.h:103
std::string type_
type of the plugin
Definition: flatland_plugin.h:60
virtual void OnInitialize(const YAML::Node &config)=0
The method for the particular model plugin to override and provide its own initialization.
Definition: flatland_plugin.h:57
Definition: timekeeper.h:55
std::string name_
name of the plugin
Definition: flatland_plugin.h:61
virtual void EndContact(b2Contact *contact)
A method that is called for all Box2D end contacts.
Definition: flatland_plugin.h:109