Model.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 /* 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 #include "gazebo/util/system.hh"
35 
36 namespace boost
37 {
38  class recursive_mutex;
39 }
40 
41 namespace gazebo
42 {
43  namespace physics
44  {
45  class Gripper;
46 
49 
52  class GAZEBO_VISIBLE 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: void LoadJoints();
67 
69  public: virtual void Init();
70 
72  public: void Update();
73 
75  public: virtual void Fini();
76 
79  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
80 
83  public: virtual const sdf::ElementPtr GetSDF();
84 
87  public: virtual void RemoveChild(EntityPtr _child);
88  using Base::RemoveChild;
89 
91  public: void Reset();
92 
95  public: void ResetPhysicsStates();
96 
99  public: void SetLinearVel(const math::Vector3 &_vel);
100 
103  public: void SetAngularVel(const math::Vector3 &_vel);
104 
108  public: void SetLinearAccel(const math::Vector3 &_vel);
109 
113  public: void SetAngularAccel(const math::Vector3 &_vel);
114 
117  public: virtual math::Vector3 GetRelativeLinearVel() const;
118 
121  public: virtual math::Vector3 GetWorldLinearVel() const;
122 
125  public: virtual math::Vector3 GetRelativeAngularVel() const;
126 
129  public: virtual math::Vector3 GetWorldAngularVel() const;
130 
133  public: virtual math::Vector3 GetRelativeLinearAccel() const;
134 
137  public: virtual math::Vector3 GetWorldLinearAccel() const;
138 
141  public: virtual math::Vector3 GetRelativeAngularAccel() const;
142 
145  public: virtual math::Vector3 GetWorldAngularAccel() const;
146 
149  public: virtual math::Box GetBoundingBox() const;
150 
153  public: unsigned int GetJointCount() const;
154 
158  public: const Link_V &GetLinks() const;
159 
162  public: const Joint_V &GetJoints() const;
163 
167  public: JointPtr GetJoint(const std::string &name);
168 
173  public: LinkPtr GetLinkById(unsigned int _id) const;
175 
179  public: LinkPtr GetLink(const std::string &_name ="canonical") const;
180 
183  public: void SetGravityMode(const bool &_value);
184 
189  public: void SetCollideMode(const std::string &_mode);
190 
193  public: void SetLaserRetro(const float _retro);
194 
197  public: virtual void FillMsg(msgs::Model &_msg);
198 
201  public: void ProcessMsg(const msgs::Model &_msg);
202 
207  public: void SetJointPosition(const std::string &_jointName,
208  double _position, int _index = 0);
209 
213  public: void SetJointPositions(
214  const std::map<std::string, double> &_jointPositions);
215 
220  public: void SetJointAnimation(
221  const std::map<std::string, common::NumericAnimationPtr> &_anims,
222  boost::function<void()> _onComplete = NULL);
223 
225  public: virtual void StopAnimation();
226 
241  public: void AttachStaticModel(ModelPtr &_model, math::Pose _offset);
242 
246  public: void DetachStaticModel(const std::string &_model);
247 
250  public: void SetState(const ModelState &_state);
251 
254  public: void SetScale(const math::Vector3 &_scale);
255 
258  public: void SetEnabled(bool _enabled);
259 
266  public: void SetLinkWorldPose(const math::Pose &_pose,
267  std::string _linkName);
268 
275  public: void SetLinkWorldPose(const math::Pose &_pose,
276  const LinkPtr &_link);
277 
281  public: void SetAutoDisable(bool _disable);
282 
285  public: bool GetAutoDisable() const;
286 
290  public: void LoadPlugins();
291 
294  public: unsigned int GetPluginCount() const;
295 
299  public: unsigned int GetSensorCount() const;
300 
303  public: JointControllerPtr GetJointController();
304 
307  public: GripperPtr GetGripper(size_t _index) const;
308 
312  public: size_t GetGripperCount() const;
313 
317  public: double GetWorldEnergyPotential() const;
318 
323  public: double GetWorldEnergyKinetic() const;
324 
329  public: double GetWorldEnergy() const;
330 
332  protected: virtual void OnPoseChange();
333 
335  private: void LoadLinks();
336 
339  private: void LoadJoint(sdf::ElementPtr _sdf);
340 
343  private: void LoadPlugin(sdf::ElementPtr _sdf);
344 
347  private: void LoadGripper(sdf::ElementPtr _sdf);
348 
352  private: void RemoveLink(const std::string &_name);
353 
355  protected: std::vector<ModelPtr> attachedModels;
356 
358  protected: std::vector<math::Pose> attachedModelsOffset;
359 
362 
364  private: LinkPtr canonicalLink;
365 
367  private: Joint_V joints;
368 
370  private: Link_V links;
371 
373  private: std::vector<GripperPtr> grippers;
374 
376  private: std::vector<ModelPluginPtr> plugins;
377 
379  private: std::map<std::string, common::NumericAnimationPtr>
380  jointAnimations;
381 
383  private: boost::function<void()> onJointAnimationComplete;
384 
386  private: mutable boost::recursive_mutex updateMutex;
387 
389  private: JointControllerPtr jointController;
390  };
392  }
393 }
394 #endif
std::vector< JointPtr > Joint_V
Definition: PhysicsTypes.hh:178
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:66
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:82
transport::PublisherPtr jointPub
Publisher for joint info.
Definition: Model.hh:361
Encapsulates a position and rotation in three space.
Definition: Pose.hh:40
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:43
Mathematical representation of a box and related functions.
Definition: Box.hh:33
std::vector< math::Pose > attachedModelsOffset
used by Model::AttachStaticModel
Definition: Model.hh:358
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:186
default namespace for gazebo
A model is a collection of links, joints, and plugins.
Definition: Model.hh:52
boost::shared_ptr< JointController > JointControllerPtr
Definition: PhysicsTypes.hh:102
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:74
virtual void RemoveChild(unsigned int _id)
Remove a child from this entity.
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:98
#define NULL
Definition: CommonTypes.hh:30
Base class for all physics objects in Gazebo.
Definition: Entity.hh:56
std::vector< ModelPtr > attachedModels
used by Model::AttachStaticModel
Definition: Model.hh:355
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
Store state information of a physics::Model object.
Definition: ModelState.hh:50
boost::shared_ptr< Gripper > GripperPtr
Definition: PhysicsTypes.hh:162
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
#define GAZEBO_VISIBLE
Use to represent "symbol visible" if supported.
Definition: system.hh:48
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:90