47 #ifndef FLATLAND_SERVER_MODEL_PLUGIN_H 48 #define FLATLAND_SERVER_MODEL_PLUGIN_H 50 #include <Box2D/Box2D.h> 51 #include <flatland_server/flatland_plugin.h> 52 #include <flatland_server/model.h> 53 #include <flatland_server/timekeeper.h> 55 #include <yaml-cpp/yaml.h> 84 void Initialize(
const std::string &type,
const std::string &name,
85 Model *model,
const YAML::Node &config);
101 b2Fixture *&this_fixture, b2Fixture *&other_fixture);
117 #endif // FLATLAND_SERVER_MODEL_PLUGIN_H ModelPlugin()=default
Model plugin default constructor.
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...
Definition: model_plugin.cpp:63
ros::NodeHandle nh_
ROS node handle.
Definition: model_plugin.h:69
Definition: flatland_plugin.h:57
Model * GetModel()
Get model.
Definition: model_plugin.cpp:51
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 defaul...
Definition: model_plugin.cpp:53
Definition: model_plugin.h:64