1 #ifndef GAZEBO_MODEL_ATTACHMENT_PLUGIN_H
2 #define GAZEBO_MODEL_ATTACHMENT_PLUGIN_H
4 #include <boost/thread.hpp>
5 #include <boost/thread/mutex.hpp>
6 #include <gazebo_model_attachment_plugin/Attach.h>
7 #include <gazebo_model_attachment_plugin/Detach.h>
10 #include <gazebo/common/Events.hh>
11 #include <gazebo/common/Plugin.hh>
12 #include <gazebo/physics/physics.hh>
13 #include <gazebo/transport/TransportTypes.hh>
14 #include <gazebo/transport/transport.hh>
31 void Load(physics::WorldPtr world, sdf::ElementPtr sdf);
36 bool attachCallback(gazebo_model_attachment_plugin::Attach::Request& req,
37 gazebo_model_attachment_plugin::Attach::Response& res);
38 bool detachCallback(gazebo_model_attachment_plugin::Detach::Request& req,
39 gazebo_model_attachment_plugin::Detach::Response& res);
41 void attach(
const std::string& joint_name, physics::ModelPtr m1, physics::ModelPtr m2, physics::LinkPtr l1,
43 void detach(
const std::string& joint_name, physics::ModelPtr m1, physics::ModelPtr m2);