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 (C) 2012-2014 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 #include <boost/thread/recursive_mutex.hpp>
29 
33 #include "gazebo/physics/Entity.hh"
34 
35 namespace boost
36 {
37  class recursive_mutex;
38 }
39 
40 namespace gazebo
41 {
42  namespace physics
43  {
44  class Gripper;
45 
48 
51  class Model : public Entity
52  {
55  public: explicit Model(BasePtr _parent);
56 
58  public: virtual ~Model();
59 
62  public: void Load(sdf::ElementPtr _sdf);
63 
65  public: void LoadJoints();
66 
68  public: virtual void Init();
69 
71  public: void Update();
72 
74  public: virtual void Fini();
75 
78  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
79 
82  public: virtual const sdf::ElementPtr GetSDF();
83 
86  public: virtual void RemoveChild(EntityPtr _child);
87 
89  public: void Reset();
90 
93  public: void SetLinearVel(const math::Vector3 &_vel);
94 
97  public: void SetAngularVel(const math::Vector3 &_vel);
98 
102  public: void SetLinearAccel(const math::Vector3 &_vel);
103 
107  public: void SetAngularAccel(const math::Vector3 &_vel);
108 
111  public: virtual math::Vector3 GetRelativeLinearVel() const;
112 
115  public: virtual math::Vector3 GetWorldLinearVel() const;
116 
119  public: virtual math::Vector3 GetRelativeAngularVel() const;
120 
123  public: virtual math::Vector3 GetWorldAngularVel() const;
124 
127  public: virtual math::Vector3 GetRelativeLinearAccel() const;
128 
131  public: virtual math::Vector3 GetWorldLinearAccel() const;
132 
135  public: virtual math::Vector3 GetRelativeAngularAccel() const;
136 
139  public: virtual math::Vector3 GetWorldAngularAccel() const;
140 
143  public: virtual math::Box GetBoundingBox() const;
144 
147  public: unsigned int GetJointCount() const;
148 
152  public: Link_V GetLinks() const;
153 
156  public: const Joint_V &GetJoints() const;
157 
161  public: JointPtr GetJoint(const std::string &name);
162 
167  public: LinkPtr GetLinkById(unsigned int _id) const;
169 
173  public: LinkPtr GetLink(const std::string &_name ="canonical") const;
174 
177  public: void SetGravityMode(const bool &_value);
178 
183  public: void SetCollideMode(const std::string &_mode);
184 
187  public: void SetLaserRetro(const float _retro);
188 
191  public: virtual void FillMsg(msgs::Model &_msg);
192 
195  public: void ProcessMsg(const msgs::Model &_msg);
196 
201  public: void SetJointPosition(const std::string &_jointName,
202  double _position, int _index = 0);
203 
207  public: void SetJointPositions(
208  const std::map<std::string, double> &_jointPositions);
209 
214  public: void SetJointAnimation(
215  const std::map<std::string, common::NumericAnimationPtr> _anim,
216  boost::function<void()> _onComplete = NULL);
217 
219  public: virtual void StopAnimation();
220 
235  public: void AttachStaticModel(ModelPtr &_model, math::Pose _offset);
236 
240  public: void DetachStaticModel(const std::string &_model);
241 
244  public: void SetState(const ModelState &_state);
245 
248  public: void SetScale(const math::Vector3 &_scale);
249 
252  public: void SetEnabled(bool _enabled);
253 
260  public: void SetLinkWorldPose(const math::Pose &_pose,
261  std::string _linkName);
262 
269  public: void SetLinkWorldPose(const math::Pose &_pose,
270  const LinkPtr &_link);
271 
275  public: void SetAutoDisable(bool _disable);
276 
279  public: bool GetAutoDisable() const;
280 
284  public: void LoadPlugins();
285 
288  public: unsigned int GetPluginCount() const;
289 
293  public: unsigned int GetSensorCount() const;
294 
298 
301  public: GripperPtr GetGripper(size_t _index) const;
302 
306  public: size_t GetGripperCount() const;
307 
309  protected: virtual void OnPoseChange();
310 
312  private: void LoadLinks();
313 
316  private: void LoadJoint(sdf::ElementPtr _sdf);
317 
320  private: void LoadPlugin(sdf::ElementPtr _sdf);
321 
324  private: void LoadGripper(sdf::ElementPtr _sdf);
325 
329  private: void RemoveLink(const std::string &_name);
330 
332  protected: std::vector<ModelPtr> attachedModels;
333 
335  protected: std::vector<math::Pose> attachedModelsOffset;
336 
339 
341  private: LinkPtr canonicalLink;
342 
344  private: Joint_V joints;
345 
347  private: Link_V links;
348 
350  private: std::vector<GripperPtr> grippers;
351 
353  private: std::vector<ModelPluginPtr> plugins;
354 
356  private: std::map<std::string, common::NumericAnimationPtr>
357  jointAnimations;
358 
360  private: boost::function<void()> onJointAnimationComplete;
361 
363  private: common::Time prevAnimationTime;
364 
366  private: mutable boost::recursive_mutex updateMutex;
367 
369  private: JointControllerPtr jointController;
370 
372  private: bool pluginsLoaded;
373  };
375  }
376 }
377 #endif