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 2011 Nate Koenig
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 
29 #include "common/CommonTypes.hh"
30 #include "physics/PhysicsTypes.hh"
31 
32 #include "physics/ModelState.hh"
33 #include "physics/Entity.hh"
34 
35 namespace boost
36 {
37  class recursive_mutex;
38 }
39 
40 namespace gazebo
41 {
42  namespace physics
43  {
44  class JointController;
45  class Gripper;
46 
49 
52  class Model : public Entity
53  {
56  public: explicit Model(BasePtr _parent);
57 
59  public: virtual ~Model();
60 
63  public: void Load(sdf::ElementPtr _sdf);
64 
66  public: virtual void Init();
67 
69  public: void Update();
70 
72  public: virtual void Fini();
73 
76  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
77 
80  public: virtual const sdf::ElementPtr GetSDF();
81 
84  public: virtual void RemoveChild(EntityPtr _child);
85 
87  public: void Reset();
88 
91  public: void SetLinearVel(const math::Vector3 &_vel);
92 
95  public: void SetAngularVel(const math::Vector3 &_vel);
96 
100  public: void SetLinearAccel(const math::Vector3 &_vel);
101 
105  public: void SetAngularAccel(const math::Vector3 &_vel);
106 
109  public: virtual math::Vector3 GetRelativeLinearVel() const;
110 
113  public: virtual math::Vector3 GetWorldLinearVel() const;
114 
117  public: virtual math::Vector3 GetRelativeAngularVel() const;
118 
121  public: virtual math::Vector3 GetWorldAngularVel() const;
122 
125  public: virtual math::Vector3 GetRelativeLinearAccel() const;
126 
129  public: virtual math::Vector3 GetWorldLinearAccel() const;
130 
133  public: virtual math::Vector3 GetRelativeAngularAccel() const;
134 
137  public: virtual math::Vector3 GetWorldAngularAccel() const;
138 
141  public: virtual math::Box GetBoundingBox() const;
142 
145  public: unsigned int GetJointCount() const;
146 
150  public: Link_V GetAllLinks() const;
151 
155  public: JointPtr GetJoint(unsigned int _index) const;
156 
160  public: JointPtr GetJoint(const std::string &_name);
161 
164  public: LinkPtr GetLinkById(unsigned int _id) const;
165 
169  public: LinkPtr GetLink(const std::string &_name ="canonical") const;
170 
174  public: LinkPtr GetLink(unsigned int _index) const;
175 
178  public: void SetGravityMode(const bool &_value);
179 
184  public: void SetCollideMode(const std::string &_mode);
185 
188  public: void SetLaserRetro(const float _retro);
189 
191  public: void FillModelMsg(msgs::Model &_msg) GAZEBO_DEPRECATED;
192 
195  public: void FillMsg(msgs::Model &_msg);
196 
199  public: void ProcessMsg(const msgs::Model &_msg);
200 
205  public: void SetJointPosition(const std::string &_jointName,
206  double _position);
207 
211  public: void SetJointPositions(
212  const std::map<std::string, double> &_jointPositions);
213 
218  public: void SetJointAnimation(
219  const std::map<std::string, common::NumericAnimationPtr> _anim,
220  boost::function<void()> _onComplete = NULL);
221 
223  public: virtual void StopAnimation();
224 
239  public: void AttachStaticModel(ModelPtr &_model, math::Pose _offset);
240 
244  public: void DetachStaticModel(const std::string &_model);
245 
248  public: ModelState GetState();
249 
252  public: void SetState(const ModelState &_state);
253 
256  public: void SetEnabled(bool _enabled);
257 
264  public: void SetLinkWorldPose(const math::Pose &_pose,
265  std::string _linkName);
266 
273  public: void SetLinkWorldPose(const math::Pose &_pose,
274  const LinkPtr &_link);
275 
279  public: void SetAutoDisable(bool _disable);
280 
284  public: void LoadPlugins();
285 
287  protected: virtual void OnPoseChange();
288 
291  private: void LoadJoint(sdf::ElementPtr _sdf);
292 
295  private: void LoadPlugin(sdf::ElementPtr _sdf);
296 
299  private: void LoadGripper(sdf::ElementPtr _sdf);
300 
302  private: LinkPtr canonicalLink;
303 
305  private: Joint_V joints;
306 
308  private: std::vector<Gripper*> grippers;
309 
311  private: std::vector<ModelPluginPtr> plugins;
312 
314  private: transport::PublisherPtr jointPub;
315 
317  private: std::map<std::string, common::NumericAnimationPtr>
318  jointAnimations;
319 
321  private: boost::function<void()> onJointAnimationComplete;
322 
324  private: common::Time prevAnimationTime;
325 
327  private: boost::recursive_mutex *updateMutex;
328 
330  private: JointController *jointController;
331 
333  protected: std::vector<ModelPtr> attachedModels;
334 
336  protected: std::vector<math::Pose> attachedModelsOffset;
337  };
339  }
340 }
341 #endif