All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Model.hh
Go to the documentation of this file.
1 /*
2  * Copyright 2012 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 /* Desc: Base class for all models
18  * Author: Nathan Koenig and Andrew Howard
19  * Date: 8 May 2003
20  */
21 
22 #ifndef _MODEL_HH_
23 #define _MODEL_HH_
24 
25 #include <string>
26 #include <map>
27 #include <vector>
28 
32 #include "gazebo/physics/Entity.hh"
33 
34 namespace boost
35 {
36  class recursive_mutex;
37 }
38 
39 namespace gazebo
40 {
41  namespace physics
42  {
43  class Gripper;
44 
47 
50  class Model : public Entity
51  {
54  public: explicit Model(BasePtr _parent);
55 
57  public: virtual ~Model();
58 
61  public: void Load(sdf::ElementPtr _sdf);
62 
64  public: void LoadJoints();
65 
67  public: virtual void Init();
68 
70  public: void Update();
71 
73  public: virtual void Fini();
74 
77  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
78 
81  public: virtual const sdf::ElementPtr GetSDF();
82 
85  public: virtual void RemoveChild(EntityPtr _child);
86 
88  public: void Reset();
89 
92  public: void SetLinearVel(const math::Vector3 &_vel);
93 
96  public: void SetAngularVel(const math::Vector3 &_vel);
97 
101  public: void SetLinearAccel(const math::Vector3 &_vel);
102 
106  public: void SetAngularAccel(const math::Vector3 &_vel);
107 
110  public: virtual math::Vector3 GetRelativeLinearVel() const;
111 
114  public: virtual math::Vector3 GetWorldLinearVel() const;
115 
118  public: virtual math::Vector3 GetRelativeAngularVel() const;
119 
122  public: virtual math::Vector3 GetWorldAngularVel() const;
123 
126  public: virtual math::Vector3 GetRelativeLinearAccel() const;
127 
130  public: virtual math::Vector3 GetWorldLinearAccel() const;
131 
134  public: virtual math::Vector3 GetRelativeAngularAccel() const;
135 
138  public: virtual math::Vector3 GetWorldAngularAccel() const;
139 
142  public: virtual math::Box GetBoundingBox() const;
143 
146  public: unsigned int GetJointCount() const;
147 
151  public: Link_V GetLinks() const;
152 
155  public: const Joint_V &GetJoints() const;
156 
160  public: JointPtr GetJoint(const std::string &name);
161 
166  public: LinkPtr GetLinkById(unsigned int _id) const;
168 
172  public: LinkPtr GetLink(const std::string &_name ="canonical") const;
173 
176  public: void SetGravityMode(const bool &_value);
177 
182  public: void SetCollideMode(const std::string &_mode);
183 
186  public: void SetLaserRetro(const float _retro);
187 
190  public: void FillMsg(msgs::Model &_msg);
191 
194  public: void ProcessMsg(const msgs::Model &_msg);
195 
200  public: void SetJointPosition(const std::string &_jointName,
201  double _position, int _index = 0);
202 
206  public: void SetJointPositions(
207  const std::map<std::string, double> &_jointPositions);
208 
213  public: void SetJointAnimation(
214  const std::map<std::string, common::NumericAnimationPtr> _anim,
215  boost::function<void()> _onComplete = NULL);
216 
218  public: virtual void StopAnimation();
219 
234  public: void AttachStaticModel(ModelPtr &_model, math::Pose _offset);
235 
239  public: void DetachStaticModel(const std::string &_model);
240 
241 
244  public: void SetState(const ModelState &_state);
245 
248  public: void SetEnabled(bool _enabled);
249 
256  public: void SetLinkWorldPose(const math::Pose &_pose,
257  std::string _linkName);
258 
265  public: void SetLinkWorldPose(const math::Pose &_pose,
266  const LinkPtr &_link);
267 
271  public: void SetAutoDisable(bool _disable);
272 
275  public: bool GetAutoDisable() const;
276 
280  public: void LoadPlugins();
281 
284  public: unsigned int GetPluginCount() const;
285 
289  public: unsigned int GetSensorCount() const;
290 
292  protected: virtual void OnPoseChange();
293 
295  private: void LoadLinks();
296 
299  private: void LoadJoint(sdf::ElementPtr _sdf);
300 
303  private: void LoadPlugin(sdf::ElementPtr _sdf);
304 
307  private: void LoadGripper(sdf::ElementPtr _sdf);
308 
312  { return this->jointController; }
313 
315  protected: std::vector<ModelPtr> attachedModels;
316 
318  protected: std::vector<math::Pose> attachedModelsOffset;
320  private: LinkPtr canonicalLink;
321 
323  private: Joint_V joints;
324 
326  private: std::vector<Gripper*> grippers;
327 
329  private: std::vector<ModelPluginPtr> plugins;
330 
332  private: transport::PublisherPtr jointPub;
333 
335  private: std::map<std::string, common::NumericAnimationPtr>
336  jointAnimations;
337 
339  private: boost::function<void()> onJointAnimationComplete;
340 
342  private: common::Time prevAnimationTime;
343 
345  private: boost::recursive_mutex *updateMutex;
346 
348  private: JointControllerPtr jointController;
349 
350  private: bool pluginsLoaded;
351  };
353  }
354 }
355 #endif