Gripper.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2015 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef _GRIPPER_HH_
18 #define _GRIPPER_HH_
19 
20 #include <map>
21 #include <vector>
22 #include <string>
23 
24 #include "gazebo/msgs/msgs.hh"
26 #include "gazebo/math/Pose.hh"
28 #include "gazebo/util/system.hh"
29 
30 namespace gazebo
31 {
32  namespace physics
33  {
36 
45  {
48  public: explicit Gripper(ModelPtr _model);
49 
51  public: virtual ~Gripper();
52 
56  public: virtual void Load(sdf::ElementPtr _sdf);
57 
59  public: virtual void Init();
60 
62  public: std::string GetName() const;
63 
67  public: bool IsAttached() const;
68 
70  private: void OnUpdate();
71 
74  private: void OnContacts(ConstContactsPtr &_msg);
75 
77  private: void HandleAttach();
78 
80  private: void HandleDetach();
81 
83  private: void ResetDiffs();
84 
86  private: physics::ModelPtr model;
87 
89  private: physics::PhysicsEnginePtr physics;
90 
92  private: physics::WorldPtr world;
93 
95  private: physics::JointPtr fixedJoint;
96 
98  private: physics::LinkPtr palmLink;
99 
101  private: std::vector<event::ConnectionPtr> connections;
102 
104  private: std::map<std::string, physics::CollisionPtr> collisions;
105 
107  private: std::vector<msgs::Contact> contacts;
108 
110  private: boost::mutex mutexContacts;
111 
113  private: bool attached;
114 
117  private: math::Pose prevDiff;
118 
120  private: std::vector<double> diffs;
121 
123  private: int diffIndex;
124 
126  private: common::Time updateRate;
127 
129  private: common::Time prevUpdateTime;
130 
133  private: int posCount;
134 
137  private: int zeroCount;
138 
140  private: unsigned int minContactCount;
141 
143  private: int attachSteps;
144 
146  private: int detachSteps;
147 
149  private: std::string name;
150 
153 
155  private: transport::SubscriberPtr contactSub;
156  };
158  }
159 }
160 #endif
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:84
#define GZ_PHYSICS_VISIBLE
Definition: system.hh:318
Encapsulates a position and rotation in three space.
Definition: Pose.hh:37
transport::NodePtr node
Node for communication.
Definition: Gripper.hh:152
boost::shared_ptr< Subscriber > SubscriberPtr
Definition: TransportTypes.hh:53
Forward declarations for transport.
default namespace for gazebo
boost::shared_ptr< PhysicsEngine > PhysicsEnginePtr
Definition: PhysicsTypes.hh:108
A gripper abstraction.
Definition: Gripper.hh:44
boost::shared_ptr< World > WorldPtr
Definition: PhysicsTypes.hh:80
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:100
boost::shared_ptr< Node > NodePtr
Definition: TransportTypes.hh:57
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:92
A Time class, can be used to hold wall- or sim-time.
Definition: Time.hh:39