17 #ifndef GAZEBO_PHYSICS_MODEL_HH_ 18 #define GAZEBO_PHYSICS_MODEL_HH_ 24 #include <boost/function.hpp> 25 #include <boost/thread/recursive_mutex.hpp> 36 class recursive_mutex;
66 public:
virtual ~
Model();
70 public:
void Load(sdf::ElementPtr _sdf)
override;
73 public:
void LoadJoints();
76 public:
virtual void Init()
override;
79 public:
void Update()
override;
82 public:
virtual void Fini()
override;
86 public:
virtual void UpdateParameters(sdf::ElementPtr _sdf)
override;
90 public:
virtual const sdf::ElementPtr GetSDF()
override;
94 public:
const sdf::Model *GetSDFDom()
const;
101 public:
virtual const sdf::ElementPtr UnscaledSDF();
105 public:
virtual void RemoveChild(
EntityPtr _child);
106 using Base::RemoveChild;
109 public:
void Reset()
override;
114 public:
void ResetPhysicsStates();
118 public:
void SetLinearVel(
const ignition::math::Vector3d &_vel);
122 public:
void SetAngularVel(
const ignition::math::Vector3d &_vel);
127 public:
virtual ignition::math::Vector3d RelativeLinearVel()
const 133 public:
virtual ignition::math::Vector3d WorldLinearVel()
const 139 public:
virtual ignition::math::Vector3d RelativeAngularVel()
const 145 public:
virtual ignition::math::Vector3d WorldAngularVel()
const 151 public:
virtual ignition::math::Vector3d RelativeLinearAccel()
const 157 public:
virtual ignition::math::Vector3d WorldLinearAccel()
const 163 public:
virtual ignition::math::Vector3d RelativeAngularAccel()
const 169 public:
virtual ignition::math::Vector3d WorldAngularAccel()
const 174 public:
virtual ignition::math::AxisAlignedBox BoundingBox()
const 179 public:
unsigned int GetJointCount()
const;
184 public:
ModelPtr NestedModel(
const std::string &_name)
const;
188 public:
const Model_V &NestedModels()
const;
193 public:
const Link_V &GetLinks()
const;
197 public:
const Joint_V &GetJoints()
const;
202 public:
JointPtr GetJoint(
const std::string &name);
208 public:
LinkPtr GetLinkById(
unsigned int _id)
const;
214 public:
LinkPtr GetLink(
const std::string &_name =
"canonical")
const;
223 public:
virtual bool GetSelfCollide()
const;
228 public:
virtual void SetSelfCollide(
bool _self_collide);
232 public:
void SetGravityMode(
const bool &_value);
238 public:
void SetCollideMode(
const std::string &_mode);
242 public:
void SetLaserRetro(
const float _retro);
246 public:
virtual void FillMsg(msgs::Model &_msg);
250 public:
void ProcessMsg(
const msgs::Model &_msg);
256 public:
void SetJointPosition(
const std::string &_jointName,
257 double _position,
int _index = 0);
262 public:
void SetJointPositions(
263 const std::map<std::string, double> &_jointPositions);
269 public:
void SetJointAnimation(
270 const std::map<std::string, common::NumericAnimationPtr> &_anims,
271 boost::function<
void()> _onComplete =
NULL);
274 public:
virtual void StopAnimation()
override;
290 public:
void AttachStaticModel(
ModelPtr &_model,
291 ignition::math::Pose3d _offset);
296 public:
void DetachStaticModel(
const std::string &_model);
300 public:
void SetState(
const ModelState &_state);
307 public:
void SetScale(
const ignition::math::Vector3d &_scale,
308 const bool _publish =
false);
314 public: ignition::math::Vector3d Scale()
const;
318 public:
void SetEnabled(
bool _enabled);
326 public:
void SetLinkWorldPose(
const ignition::math::Pose3d &_pose,
327 std::string _linkName);
335 public:
void SetLinkWorldPose(
const ignition::math::Pose3d &_pose,
341 public:
void SetAutoDisable(
bool _disable);
345 public:
bool GetAutoDisable()
const;
350 public:
void LoadPlugins();
354 public:
unsigned int GetPluginCount()
const;
359 public:
unsigned int GetSensorCount()
const;
373 public: std::vector<std::string> SensorScopedName(
374 const std::string &_name)
const;
382 public:
GripperPtr GetGripper(
size_t _index)
const;
387 public:
size_t GetGripperCount()
const;
392 public:
double GetWorldEnergyPotential()
const;
398 public:
double GetWorldEnergyKinetic()
const;
404 public:
double GetWorldEnergy()
const;
419 const std::string &_name,
const std::string &_type,
432 sdf::ElementPtr _sdf);
437 public:
virtual bool RemoveJoint(
const std::string &_name);
441 public:
virtual void SetWindMode(
const bool _mode);
445 public:
virtual bool WindMode()
const;
449 public: boost::shared_ptr<Model> shared_from_this();
455 public:
LinkPtr CreateLink(
const std::string &_name);
474 public:
void PluginInfo(
const common::URI &_pluginUri,
475 ignition::msgs::Plugin_V &_plugins,
bool &_success);
478 public: std::optional<sdf::SemanticPose> SDFSemanticPose()
const override;
481 protected:
virtual void OnPoseChange()
override;
484 protected:
virtual void RegisterIntrospectionItems()
override;
487 private:
void LoadLinks();
490 private:
void LoadModels();
494 private:
void LoadJoint(sdf::ElementPtr _sdf);
498 private:
void LoadPlugin(sdf::ElementPtr _sdf);
502 private:
void LoadGripper(sdf::ElementPtr _sdf);
507 private:
void RemoveLink(
const std::string &_name);
510 private:
virtual void PublishScale();
522 private:
LinkPtr canonicalLink;
534 private: std::vector<GripperPtr> grippers;
537 private: std::vector<ModelPluginPtr> plugins;
540 private: std::map<std::string, common::NumericAnimationPtr>
544 private: boost::function<void()> onJointAnimationComplete;
550 private:
mutable boost::recursive_mutex updateMutex;
553 private: std::mutex receiveMutex;
558 private: std::unique_ptr<sdf::Model> modelSDFDomIsolated;
561 private:
const sdf::Model *modelSDFDom =
nullptr;
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
std::vector< LinkPtr > Link_V
Definition: PhysicsTypes.hh:226
boost::shared_ptr< Base > BasePtr
Definition: PhysicsTypes.hh:78