Model.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2016 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/function.hpp>
29 #include <boost/thread/recursive_mutex.hpp>
30 
34 #include "gazebo/physics/Entity.hh"
35 #include "gazebo/util/system.hh"
36 
37 namespace boost
38 {
39  class recursive_mutex;
40 }
41 
42 namespace gazebo
43 {
44  namespace physics
45  {
46  class Gripper;
47 
50 
53  class GZ_PHYSICS_VISIBLE Model : public Entity
54  {
57  public: explicit Model(BasePtr _parent);
58 
60  public: virtual ~Model();
61 
64  public: void Load(sdf::ElementPtr _sdf);
65 
67  public: void LoadJoints();
68 
70  public: virtual void Init();
71 
73  public: void Update();
74 
76  public: virtual void Fini();
77 
80  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
81 
84  public: virtual const sdf::ElementPtr GetSDF();
85 
91  public: virtual const sdf::ElementPtr UnscaledSDF();
92 
95  public: virtual void RemoveChild(EntityPtr _child);
96  using Base::RemoveChild;
97 
99  public: void Reset();
100  using Entity::Reset;
101 
104  public: void ResetPhysicsStates();
105 
108  public: void SetLinearVel(const math::Vector3 &_vel);
109 
112  public: void SetAngularVel(const math::Vector3 &_vel);
113 
117  public: void SetLinearAccel(const math::Vector3 &_vel);
118 
122  public: void SetAngularAccel(const math::Vector3 &_vel);
123 
126  public: virtual math::Vector3 GetRelativeLinearVel() const;
127 
130  public: virtual math::Vector3 GetWorldLinearVel() const;
131 
134  public: virtual math::Vector3 GetRelativeAngularVel() const;
135 
138  public: virtual math::Vector3 GetWorldAngularVel() const;
139 
142  public: virtual math::Vector3 GetRelativeLinearAccel() const;
143 
146  public: virtual math::Vector3 GetWorldLinearAccel() const;
147 
150  public: virtual math::Vector3 GetRelativeAngularAccel() const;
151 
154  public: virtual math::Vector3 GetWorldAngularAccel() const;
155 
158  public: virtual math::Box GetBoundingBox() const;
159 
162  public: unsigned int GetJointCount() const;
163 
167  public: ModelPtr NestedModel(const std::string &_name) const;
168 
171  public: const Model_V &NestedModels() const;
172 
176  public: const Link_V &GetLinks() const;
177 
180  public: const Joint_V &GetJoints() const;
181 
185  public: JointPtr GetJoint(const std::string &name);
186 
191  public: LinkPtr GetLinkById(unsigned int _id) const;
193 
197  public: LinkPtr GetLink(const std::string &_name ="canonical") const;
198 
206  public: virtual bool GetSelfCollide() const;
207 
211  public: virtual void SetSelfCollide(bool _self_collide);
212 
215  public: void SetGravityMode(const bool &_value);
216 
221  public: void SetCollideMode(const std::string &_mode);
222 
225  public: void SetLaserRetro(const float _retro);
226 
229  public: virtual void FillMsg(msgs::Model &_msg);
230 
233  public: void ProcessMsg(const msgs::Model &_msg);
234 
239  public: void SetJointPosition(const std::string &_jointName,
240  double _position, int _index = 0);
241 
245  public: void SetJointPositions(
246  const std::map<std::string, double> &_jointPositions);
247 
252  public: void SetJointAnimation(
253  const std::map<std::string, common::NumericAnimationPtr> &_anims,
254  boost::function<void()> _onComplete = NULL);
255 
257  public: virtual void StopAnimation();
258 
273  public: void AttachStaticModel(ModelPtr &_model, math::Pose _offset);
274 
278  public: void DetachStaticModel(const std::string &_model);
279 
282  public: void SetState(const ModelState &_state);
283 
287  public: void SetScale(const math::Vector3 &_scale)
288  GAZEBO_DEPRECATED(7.0);
289 
295  public: void SetScale(const ignition::math::Vector3d &_scale,
296  const bool _publish = false);
297 
302  public: ignition::math::Vector3d Scale() const;
303 
306  public: void SetEnabled(bool _enabled);
307 
314  public: void SetLinkWorldPose(const math::Pose &_pose,
315  std::string _linkName);
316 
323  public: void SetLinkWorldPose(const math::Pose &_pose,
324  const LinkPtr &_link);
325 
329  public: void SetAutoDisable(bool _disable);
330 
333  public: bool GetAutoDisable() const;
334 
338  public: void LoadPlugins();
339 
342  public: unsigned int GetPluginCount() const;
343 
347  public: unsigned int GetSensorCount() const;
348 
351  public: JointControllerPtr GetJointController();
352 
355  public: GripperPtr GetGripper(size_t _index) const;
356 
360  public: size_t GetGripperCount() const;
361 
365  public: double GetWorldEnergyPotential() const;
366 
371  public: double GetWorldEnergyKinetic() const;
372 
377  public: double GetWorldEnergy() const;
378 
388  public: gazebo::physics::JointPtr CreateJoint(
389  const std::string &_name, const std::string &_type,
390  physics::LinkPtr _parent, physics::LinkPtr _child);
391 
395  public: bool RemoveJoint(const std::string &_name);
396 
399  public: virtual void SetWindMode(const bool _mode);
400 
403  public: virtual bool WindMode() const;
404 
407  public: boost::shared_ptr<Model> shared_from_this();
408 
413  public: LinkPtr CreateLink(const std::string &_name);
414 
416  protected: virtual void OnPoseChange();
417 
419  private: void LoadLinks();
420 
422  private: void LoadModels();
423 
426  private: void LoadJoint(sdf::ElementPtr _sdf);
427 
430  private: void LoadPlugin(sdf::ElementPtr _sdf);
431 
434  private: void LoadGripper(sdf::ElementPtr _sdf);
435 
439  private: void RemoveLink(const std::string &_name);
440 
442  private: virtual void PublishScale();
443 
445  protected: std::vector<ModelPtr> attachedModels;
446 
448  protected: std::vector<math::Pose> attachedModelsOffset;
449 
452 
454  private: LinkPtr canonicalLink;
455 
457  private: Joint_V joints;
458 
460  private: Link_V links;
461 
463  private: Model_V models;
464 
466  private: std::vector<GripperPtr> grippers;
467 
469  private: std::vector<ModelPluginPtr> plugins;
470 
472  private: std::map<std::string, common::NumericAnimationPtr>
473  jointAnimations;
474 
476  private: boost::function<void()> onJointAnimationComplete;
477 
479  private: mutable boost::recursive_mutex updateMutex;
480 
482  private: JointControllerPtr jointController;
483  };
485  }
486 }
487 #endif
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:109
std::vector< ModelPtr > Model_V
Definition: PhysicsTypes.hh:205
Encapsulates a position and rotation in three space.
Definition: Pose.hh:37
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:39
Mathematical representation of a box and related functions.
Definition: Box.hh:35
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
#define GAZEBO_DEPRECATED(version)
Definition: CommonTypes.hh:48
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:117
std::vector< math::Pose > attachedModelsOffset
used by Model::AttachStaticModel
Definition: Model.hh:448
virtual void RemoveChild(unsigned int _id)
Remove a child from this entity.
std::vector< ModelPtr > attachedModels
used by Model::AttachStaticModel
Definition: Model.hh:445
default namespace for gazebo
A model is a collection of links, joints, and plugins.
Definition: Model.hh:53
transport::PublisherPtr jointPub
Publisher for joint info.
Definition: Model.hh:451
boost::shared_ptr< Gripper > GripperPtr
Definition: PhysicsTypes.hh:197
std::vector< JointPtr > Joint_V
Definition: PhysicsTypes.hh:213
#define NULL
Definition: CommonTypes.hh:31
Base class for all physics objects in Gazebo.
Definition: Entity.hh:58
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:85
boost::shared_ptr< JointController > JointControllerPtr
Definition: PhysicsTypes.hh:121
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:93
GAZEBO_VISIBLE void Init(google::protobuf::Message &_message, const std::string &_id="")
Initialize a message.
virtual void Reset()
Reset the entity.
Store state information of a physics::Model object.
Definition: ModelState.hh:48
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:225
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:77