Model.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 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 #ifndef GAZEBO_PHYSICS_MODEL_HH_
18 #define GAZEBO_PHYSICS_MODEL_HH_
19 
20 #include <string>
21 #include <map>
22 #include <mutex>
23 #include <vector>
24 #include <boost/function.hpp>
25 #include <boost/thread/recursive_mutex.hpp>
26 
30 #include "gazebo/physics/Entity.hh"
32 #include "gazebo/util/system.hh"
33 
34 namespace boost
35 {
36  class recursive_mutex;
37 }
38 
39 // Forward declare reference and pointer parameters
40 namespace ignition
41 {
42  namespace msgs
43  {
44  class Plugin_V;
45  }
46 }
47 
48 namespace gazebo
49 {
50  namespace physics
51  {
52  class Gripper;
53 
56 
59  class GZ_PHYSICS_VISIBLE Model : public Entity
60  {
63  public: explicit Model(BasePtr _parent);
64 
66  public: virtual ~Model();
67 
70  public: void Load(sdf::ElementPtr _sdf);
71 
73  public: void LoadJoints();
74 
76  public: virtual void Init();
77 
79  public: void Update();
80 
82  public: virtual void Fini();
83 
86  public: virtual void UpdateParameters(sdf::ElementPtr _sdf);
87 
90  public: virtual const sdf::ElementPtr GetSDF();
91 
97  public: virtual const sdf::ElementPtr UnscaledSDF();
98 
101  public: virtual void RemoveChild(EntityPtr _child);
102  using Base::RemoveChild;
103 
105  public: void Reset();
106  using Entity::Reset;
107 
110  public: void ResetPhysicsStates();
111 
115  public: void SetLinearVel(const math::Vector3 &_vel)
116  GAZEBO_DEPRECATED(8.0);
117 
120  public: void SetLinearVel(const ignition::math::Vector3d &_vel);
121 
125  public: void SetAngularVel(const math::Vector3 &_vel)
126  GAZEBO_DEPRECATED(8.0);
127 
130  public: void SetAngularVel(const ignition::math::Vector3d &_vel);
131 
136  public: void SetLinearAccel(const math::Vector3 &_vel)
137  GAZEBO_DEPRECATED(8.0);
138 
142  public: void SetLinearAccel(const ignition::math::Vector3d &_vel);
143 
148  public: void SetAngularAccel(const math::Vector3 &_vel)
149  GAZEBO_DEPRECATED(8.0);
150 
154  public: void SetAngularAccel(const ignition::math::Vector3d &_vel);
155 
159  public: virtual math::Vector3 GetRelativeLinearVel() const
160  GAZEBO_DEPRECATED(8.0);
161 
165  public: virtual ignition::math::Vector3d RelativeLinearVel() const;
166 
170  public: virtual math::Vector3 GetWorldLinearVel() const
171  GAZEBO_DEPRECATED(8.0);
172 
176  public: virtual ignition::math::Vector3d WorldLinearVel() const;
177 
181  public: virtual math::Vector3 GetRelativeAngularVel() const
182  GAZEBO_DEPRECATED(8.0);
183 
187  public: virtual ignition::math::Vector3d RelativeAngularVel() const;
188 
192  public: virtual math::Vector3 GetWorldAngularVel() const
193  GAZEBO_DEPRECATED(8.0);
194 
198  public: virtual ignition::math::Vector3d WorldAngularVel() const;
199 
203  public: virtual math::Vector3 GetRelativeLinearAccel() const
204  GAZEBO_DEPRECATED(8.0);
205 
209  public: virtual ignition::math::Vector3d RelativeLinearAccel() const;
210 
214  public: virtual math::Vector3 GetWorldLinearAccel() const
215  GAZEBO_DEPRECATED(8.0);
216 
220  public: virtual ignition::math::Vector3d WorldLinearAccel() const;
221 
225  public: virtual math::Vector3 GetRelativeAngularAccel() const
226  GAZEBO_DEPRECATED(8.0);
227 
231  public: virtual ignition::math::Vector3d RelativeAngularAccel() const;
232 
236  public: virtual math::Vector3 GetWorldAngularAccel() const
237  GAZEBO_DEPRECATED(8.0);
238 
242  public: virtual ignition::math::Vector3d WorldAngularAccel() const;
243 
247  public: virtual math::Box GetBoundingBox() const
248  GAZEBO_DEPRECATED(8.0);
249 
252  public: virtual ignition::math::Box BoundingBox() const;
253 
256  public: unsigned int GetJointCount() const;
257 
261  public: ModelPtr NestedModel(const std::string &_name) const;
262 
265  public: const Model_V &NestedModels() const;
266 
270  public: const Link_V &GetLinks() const;
271 
274  public: const Joint_V &GetJoints() const;
275 
279  public: JointPtr GetJoint(const std::string &name);
280 
285  public: LinkPtr GetLinkById(unsigned int _id) const;
287 
291  public: LinkPtr GetLink(const std::string &_name ="canonical") const;
292 
300  public: virtual bool GetSelfCollide() const;
301 
305  public: virtual void SetSelfCollide(bool _self_collide);
306 
309  public: void SetGravityMode(const bool &_value);
310 
315  public: void SetCollideMode(const std::string &_mode);
316 
319  public: void SetLaserRetro(const float _retro);
320 
323  public: virtual void FillMsg(msgs::Model &_msg);
324 
327  public: void ProcessMsg(const msgs::Model &_msg);
328 
333  public: void SetJointPosition(const std::string &_jointName,
334  double _position, int _index = 0);
335 
339  public: void SetJointPositions(
340  const std::map<std::string, double> &_jointPositions);
341 
346  public: void SetJointAnimation(
347  const std::map<std::string, common::NumericAnimationPtr> &_anims,
348  boost::function<void()> _onComplete = NULL);
349 
351  public: virtual void StopAnimation();
352 
368  public: void AttachStaticModel(ModelPtr &_model, math::Pose _offset)
369  GAZEBO_DEPRECATED(8.0);
370 
385  public: void AttachStaticModel(ModelPtr &_model,
386  ignition::math::Pose3d _offset);
387 
391  public: void DetachStaticModel(const std::string &_model);
392 
395  public: void SetState(const ModelState &_state);
396 
402  public: void SetScale(const ignition::math::Vector3d &_scale,
403  const bool _publish = false);
404 
409  public: ignition::math::Vector3d Scale() const;
410 
413  public: void SetEnabled(bool _enabled);
414 
422  public: void SetLinkWorldPose(const math::Pose &_pose,
423  std::string _linkName) GAZEBO_DEPRECATED(8.0);
424 
431  public: void SetLinkWorldPose(const ignition::math::Pose3d &_pose,
432  std::string _linkName);
433 
441  public: void SetLinkWorldPose(const math::Pose &_pose,
442  const LinkPtr &_link) GAZEBO_DEPRECATED(8.0);
443 
450  public: void SetLinkWorldPose(const ignition::math::Pose3d &_pose,
451  const LinkPtr &_link);
452 
456  public: void SetAutoDisable(bool _disable);
457 
460  public: bool GetAutoDisable() const;
461 
465  public: void LoadPlugins();
466 
469  public: unsigned int GetPluginCount() const;
470 
474  public: unsigned int GetSensorCount() const;
475 
488  public: std::vector<std::string> SensorScopedName(
489  const std::string &_name) const;
490 
493  public: JointControllerPtr GetJointController();
494 
497  public: GripperPtr GetGripper(size_t _index) const;
498 
502  public: size_t GetGripperCount() const;
503 
507  public: double GetWorldEnergyPotential() const;
508 
513  public: double GetWorldEnergyKinetic() const;
514 
519  public: double GetWorldEnergy() const;
520 
530  public: gazebo::physics::JointPtr CreateJoint(
531  const std::string &_name, const std::string &_type,
532  physics::LinkPtr _parent, physics::LinkPtr _child);
533 
540  public: gazebo::physics::JointPtr CreateJoint(sdf::ElementPtr _sdf);
541 
545  public: bool RemoveJoint(const std::string &_name);
546 
549  public: virtual void SetWindMode(const bool _mode);
550 
553  public: virtual bool WindMode() const;
554 
557  public: boost::shared_ptr<Model> shared_from_this();
558 
563  public: LinkPtr CreateLink(const std::string &_name);
564 
582  public: void PluginInfo(const common::URI &_pluginUri,
583  ignition::msgs::Plugin_V &_plugins, bool &_success);
584 
586  protected: virtual void OnPoseChange();
587 
589  protected: virtual void RegisterIntrospectionItems();
590 
592  private: void LoadLinks();
593 
595  private: void LoadModels();
596 
599  private: void LoadJoint(sdf::ElementPtr _sdf);
600 
603  private: void LoadPlugin(sdf::ElementPtr _sdf);
604 
607  private: void LoadGripper(sdf::ElementPtr _sdf);
608 
612  private: void RemoveLink(const std::string &_name);
613 
615  private: virtual void PublishScale();
616 
618  protected: std::vector<ModelPtr> attachedModels;
619 
621  protected: std::vector<ignition::math::Pose3d> attachedModelsOffset;
622 
625 
627  private: LinkPtr canonicalLink;
628 
630  private: Joint_V joints;
631 
633  private: Link_V links;
634 
636  private: Model_V models;
637 
639  private: std::vector<GripperPtr> grippers;
640 
642  private: std::vector<ModelPluginPtr> plugins;
643 
645  private: std::map<std::string, common::NumericAnimationPtr>
646  jointAnimations;
647 
649  private: boost::function<void()> onJointAnimationComplete;
650 
652  private: JointControllerPtr jointController;
653 
655  private: mutable boost::recursive_mutex updateMutex;
656 
658  private: std::mutex receiveMutex;
659  };
661  }
662 }
663 #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:42
The Vector3 class represents the generic vector containing 3 elements.
Definition: Vector3.hh:44
Mathematical representation of a box and related functions.
Definition: Box.hh:41
Forward declarations for transport.
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:117
std::vector< ignition::math::Pose3d > attachedModelsOffset
used by Model::AttachStaticModel
Definition: Model.hh:621
virtual void RemoveChild(unsigned int _id)
Remove a child from this entity.
std::vector< ModelPtr > attachedModels
used by Model::AttachStaticModel
Definition: Model.hh:618
default namespace for gazebo
A complete URI.
Definition: URI.hh:176
A model is a collection of links, joints, and plugins.
Definition: Model.hh:59
transport::PublisherPtr jointPub
Publisher for joint info.
Definition: Model.hh:624
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:56
#define GAZEBO_DEPRECATED(version)
Definition: system.hh:302
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:49
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:225
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:77