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) override;
71 
73  public: void LoadJoints();
74 
76  public: virtual void Init() override;
77 
79  public: void Update() override;
80 
82  public: virtual void Fini() override;
83 
86  public: virtual void UpdateParameters(sdf::ElementPtr _sdf) override;
87 
90  public: virtual const sdf::ElementPtr GetSDF() override;
91 
94  public: const sdf::Model *GetSDFDom() const;
95 
101  public: virtual const sdf::ElementPtr UnscaledSDF();
102 
105  public: virtual void RemoveChild(EntityPtr _child);
106  using Base::RemoveChild;
107 
109  public: void Reset() override;
110  using Entity::Reset;
111 
114  public: void ResetPhysicsStates();
115 
118  public: void SetLinearVel(const ignition::math::Vector3d &_vel);
119 
122  public: void SetAngularVel(const ignition::math::Vector3d &_vel);
123 
127  public: virtual ignition::math::Vector3d RelativeLinearVel() const
128  override;
129 
133  public: virtual ignition::math::Vector3d WorldLinearVel() const
134  override;
135 
139  public: virtual ignition::math::Vector3d RelativeAngularVel() const
140  override;
141 
145  public: virtual ignition::math::Vector3d WorldAngularVel() const
146  override;
147 
151  public: virtual ignition::math::Vector3d RelativeLinearAccel() const
152  override;
153 
157  public: virtual ignition::math::Vector3d WorldLinearAccel() const
158  override;
159 
163  public: virtual ignition::math::Vector3d RelativeAngularAccel() const
164  override;
165 
169  public: virtual ignition::math::Vector3d WorldAngularAccel() const
170  override;
171 
174  public: virtual ignition::math::AxisAlignedBox BoundingBox() const
175  override;
176 
179  public: unsigned int GetJointCount() const;
180 
184  public: ModelPtr NestedModel(const std::string &_name) const;
185 
188  public: const Model_V &NestedModels() const;
189 
193  public: const Link_V &GetLinks() const;
194 
197  public: const Joint_V &GetJoints() const;
198 
202  public: JointPtr GetJoint(const std::string &name);
203 
208  public: LinkPtr GetLinkById(unsigned int _id) const;
210 
214  public: LinkPtr GetLink(const std::string &_name ="canonical") const;
215 
223  public: virtual bool GetSelfCollide() const;
224 
228  public: virtual void SetSelfCollide(bool _self_collide);
229 
232  public: void SetGravityMode(const bool &_value);
233 
238  public: void SetCollideMode(const std::string &_mode);
239 
242  public: void SetLaserRetro(const float _retro);
243 
246  public: virtual void FillMsg(msgs::Model &_msg);
247 
250  public: void ProcessMsg(const msgs::Model &_msg);
251 
256  public: void SetJointPosition(const std::string &_jointName,
257  double _position, int _index = 0);
258 
262  public: void SetJointPositions(
263  const std::map<std::string, double> &_jointPositions);
264 
269  public: void SetJointAnimation(
270  const std::map<std::string, common::NumericAnimationPtr> &_anims,
271  boost::function<void()> _onComplete = NULL);
272 
274  public: virtual void StopAnimation() override;
275 
290  public: void AttachStaticModel(ModelPtr &_model,
291  ignition::math::Pose3d _offset);
292 
296  public: void DetachStaticModel(const std::string &_model);
297 
300  public: void SetState(const ModelState &_state);
301 
307  public: void SetScale(const ignition::math::Vector3d &_scale,
308  const bool _publish = false);
309 
314  public: ignition::math::Vector3d Scale() const;
315 
318  public: void SetEnabled(bool _enabled);
319 
326  public: void SetLinkWorldPose(const ignition::math::Pose3d &_pose,
327  std::string _linkName);
328 
335  public: void SetLinkWorldPose(const ignition::math::Pose3d &_pose,
336  const LinkPtr &_link);
337 
341  public: void SetAutoDisable(bool _disable);
342 
345  public: bool GetAutoDisable() const;
346 
350  public: void LoadPlugins();
351 
354  public: unsigned int GetPluginCount() const;
355 
359  public: unsigned int GetSensorCount() const;
360 
373  public: std::vector<std::string> SensorScopedName(
374  const std::string &_name) const;
375 
378  public: JointControllerPtr GetJointController();
379 
382  public: GripperPtr GetGripper(size_t _index) const;
383 
387  public: size_t GetGripperCount() const;
388 
392  public: double GetWorldEnergyPotential() const;
393 
398  public: double GetWorldEnergyKinetic() const;
399 
404  public: double GetWorldEnergy() const;
405 
418  public: virtual gazebo::physics::JointPtr CreateJoint(
419  const std::string &_name, const std::string &_type,
420  physics::LinkPtr _parent, physics::LinkPtr _child);
421 
431  public: virtual gazebo::physics::JointPtr CreateJoint(
432  sdf::ElementPtr _sdf);
433 
437  public: virtual bool RemoveJoint(const std::string &_name);
438 
441  public: virtual void SetWindMode(const bool _mode);
442 
445  public: virtual bool WindMode() const;
446 
449  public: boost::shared_ptr<Model> shared_from_this();
450 
455  public: LinkPtr CreateLink(const std::string &_name);
456 
474  public: void PluginInfo(const common::URI &_pluginUri,
475  ignition::msgs::Plugin_V &_plugins, bool &_success);
476 
477  // Documentation inherited.
478  public: std::optional<sdf::SemanticPose> SDFSemanticPose() const override;
479 
481  protected: virtual void OnPoseChange() override;
482 
484  protected: virtual void RegisterIntrospectionItems() override;
485 
487  private: void LoadLinks();
488 
490  private: void LoadModels();
491 
494  private: void LoadJoint(sdf::ElementPtr _sdf);
495 
498  private: void LoadPlugin(sdf::ElementPtr _sdf);
499 
502  private: void LoadGripper(sdf::ElementPtr _sdf);
503 
507  private: void RemoveLink(const std::string &_name);
508 
510  private: virtual void PublishScale();
511 
513  protected: std::vector<ModelPtr> attachedModels;
514 
516  protected: std::vector<ignition::math::Pose3d> attachedModelsOffset;
517 
520 
522  private: LinkPtr canonicalLink;
523 
525  private: Joint_V joints;
526 
528  private: Link_V links;
529 
531  private: Model_V models;
532 
534  private: std::vector<GripperPtr> grippers;
535 
537  private: std::vector<ModelPluginPtr> plugins;
538 
540  private: std::map<std::string, common::NumericAnimationPtr>
541  jointAnimations;
542 
544  private: boost::function<void()> onJointAnimationComplete;
545 
547  private: JointControllerPtr jointController;
548 
550  private: mutable boost::recursive_mutex updateMutex;
551 
553  private: std::mutex receiveMutex;
554 
558  private: std::unique_ptr<sdf::Model> modelSDFDomIsolated;
559 
561  private: const sdf::Model *modelSDFDom = nullptr;
562  };
564  }
565 }
566 #endif
boost::shared_ptr< Link > LinkPtr
Definition: PhysicsTypes.hh:110
Definition: JointMaker.hh:44
Forward declarations for the common classes.
Definition: Animation.hh:26
std::vector< ModelPtr > Model_V
Definition: PhysicsTypes.hh:206
Forward declarations for transport.
boost::shared_ptr< Publisher > PublisherPtr
Definition: TransportTypes.hh:49
boost::shared_ptr< Joint > JointPtr
Definition: PhysicsTypes.hh:118
std::vector< ignition::math::Pose3d > attachedModelsOffset
used by Model::AttachStaticModel
Definition: Model.hh:516
std::vector< ModelPtr > attachedModels
used by Model::AttachStaticModel
Definition: Model.hh:513
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:519
boost::shared_ptr< Gripper > GripperPtr
Definition: PhysicsTypes.hh:198
std::vector< JointPtr > Joint_V
Definition: PhysicsTypes.hh:214
#define NULL
Definition: CommonTypes.hh:31
Base class for all physics objects in Gazebo.
Definition: Entity.hh:52
boost::shared_ptr< Entity > EntityPtr
Definition: PhysicsTypes.hh:86
boost::shared_ptr< JointController > JointControllerPtr
Definition: PhysicsTypes.hh:122
boost::shared_ptr< Model > ModelPtr
Definition: PhysicsTypes.hh:94
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:48
Definition: Model.hh:40
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:226
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:78