GazeboGripper.h
Go to the documentation of this file.
00001 #ifndef GAZEBOGRIPPER_H
00002 #define GAZEBOGRIPPER_H
00003 
00004 #include "common/Plugin.hh"
00005 #include "common/Events.hh"
00006 
00007 #include "physics/Gripper.hh"
00008 
00009 #include <ros/ros.h>
00010 #include <sensor_msgs/JointState.h>
00011 
00012 namespace gazebo
00013 {
00014     class GazeboGripper : public ModelPlugin
00015     {
00016     public:
00017         GazeboGripper();
00018         ~GazeboGripper();
00019 
00020         virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
00021         virtual void Init();
00022 
00023         // Called by the world update start event
00024         void onUpdate();
00025 
00026     private:
00027         // callback used when the gripper contacts an object
00028         void onContact(const std::string &_collisionName,
00029                                 const physics::Contact &_contact);
00030 
00031         // check contact state and handle appropriately
00032         void handleContact();
00033 
00034         // Attach linkPtr to the gripper
00035         void handleAttach(physics::LinkPtr linkPtr);
00036 
00037         // Detach an object from the gripper
00038         void handleDetach();
00039 
00040         // Pointer to the model
00041         physics::ModelPtr modelPtr;
00042         physics::JointPtr fixedJointPtr;
00043 
00044         std::vector<physics::JointPtr> jointPtrs;
00045         std::vector<physics::LinkPtr> linkPtrs;
00046         std::vector<event::ConnectionPtr> connectionPtrs;
00047 
00048         std::map<std::string, physics::CollisionPtr> collisionPtrs;
00049         std::vector<physics::Contact> contacts;
00050 
00051         bool attached;
00052         double attachWait;
00053         double detachWait;
00054         double updateTime;
00055         double maxRelativeMotionRate;
00056 
00057         std::string gripperAttachLink;
00058 
00059         common::Time prevUpdateTime;
00060         double contactDuration;
00061         double nonContactDuration;
00062         common::Time prevContactUpdateTime;
00063         math::Pose prevDiff;
00064     };
00065 }
00066 
00067 #endif


gazebo_gripper
Author(s): rctaylo2
autogenerated on Mon Oct 6 2014 02:43:43