Loading...
Searching...
No Matches
Model.hh
Go to the documentation of this file.
1/*
2 * Copyright 2018 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 SDF_MODEL_HH_
18#define SDF_MODEL_HH_
19
20#include <memory>
21#include <optional>
22#include <string>
23#include <utility>
24#include <vector>
25
26#include <gz/math/Pose3.hh>
27#include <gz/utils/ImplPtr.hh>
28#include "sdf/Element.hh"
29#include "sdf/OutputConfig.hh"
30#include "sdf/ParserConfig.hh"
31#include "sdf/Plugin.hh"
32#include "sdf/SemanticPose.hh"
33#include "sdf/Types.hh"
34#include "sdf/config.hh"
35#include "sdf/system_util.hh"
36
37namespace sdf
38{
39 // Inline bracket to help doxygen filtering.
40 inline namespace SDF_VERSION_NAMESPACE {
41 //
42
43 // Forward declarations.
44 class Frame;
45 class InterfaceModel;
46 class Joint;
47 class Link;
48 class ParserConfig;
49 class NestedInclude;
50 struct PoseRelativeToGraph;
51 struct FrameAttachedToGraph;
52 template <typename T> class ScopedGraph;
53 using InterfaceModelConstPtr = std::shared_ptr<const InterfaceModel>;
54
55
57 {
59 public: Model();
60
67 public: Errors Load(ElementPtr _sdf);
68
76 public: Errors Load(sdf::ElementPtr _sdf, const ParserConfig &_config);
77
82 public: Errors ValidateGraphs() const;
83
87 public: std::string Name() const;
88
92 public: void SetName(const std::string &_name);
93
98 public: bool Static() const;
99
104 public: void SetStatic(bool _static);
105
111 public: bool SelfCollide() const;
112
117 public: void SetSelfCollide(bool _selfCollide);
118
123 public: bool AllowAutoDisable() const;
124
129 public: void SetAllowAutoDisable(bool _allowAutoDisable);
130
135 public: bool EnableWind() const;
136
140 public: void SetEnableWind(bool _enableWind);
141
147 public: uint64_t LinkCount() const;
148
154 public: const Link *LinkByIndex(const uint64_t _index) const;
155
162 public: Link *LinkByIndex(uint64_t _index);
163
169 public: const Link *LinkByName(const std::string &_name) const;
170
176 public: Link *LinkByName(const std::string &_name);
177
183 public: bool LinkNameExists(const std::string &_name) const;
184
190 public: uint64_t JointCount() const;
191
197 public: const Joint *JointByIndex(const uint64_t _index) const;
198
205 public: Joint *JointByIndex(uint64_t _index);
206
212 public: bool JointNameExists(const std::string &_name) const;
213
221 public: const Joint *JointByName(const std::string &_name) const;
222
230 public: Joint *JointByName(const std::string &_name);
231
237 public: uint64_t FrameCount() const;
238
246 public: const Frame *FrameByIndex(const uint64_t _index) const;
247
255 public: Frame *FrameByIndex(uint64_t _index);
256
263 public: const Frame *FrameByName(const std::string &_name) const;
264
271 public: Frame *FrameByName(const std::string &_name);
272
278 public: bool FrameNameExists(const std::string &_name) const;
279
285 public: uint64_t ModelCount() const;
286
293 public: const Model *ModelByIndex(const uint64_t _index) const;
294
296 // based on an index.
301 public: Model *ModelByIndex(uint64_t _index);
302
308 public: bool ModelNameExists(const std::string &_name) const;
309
317 public: const Model *ModelByName(const std::string &_name) const;
318
326 public: Model *ModelByName(const std::string &_name);
327
333 public: const gz::math::Pose3d &RawPose() const;
334
338 public: void SetRawPose(const gz::math::Pose3d &_pose);
339
342 public: const Link *CanonicalLink() const;
343
348 public: const std::string &CanonicalLinkName() const;
349
354 public: void SetCanonicalLinkName(const std::string &_canonicalLink);
355
360 public: const std::string &PoseRelativeTo() const;
361
366 public: void SetPoseRelativeTo(const std::string &_frame);
367
372 public: sdf::ElementPtr Element() const;
373
378
381 public: const std::string &PlacementFrameName() const;
382
386 public: void SetPlacementFrameName(const std::string &_name);
387
392 // TODO(addisu): If the canonical link is inside an interface model, this
393 // function returns {nullptr, name}. This can be problematic for downstream
394 // applications.
395 public: std::pair<const Link *, std::string> CanonicalLinkAndRelativeName()
396 const;
397
402 public: uint64_t InterfaceModelCount() const;
403
410 public: std::shared_ptr<const InterfaceModel> InterfaceModelByIndex(
411 const uint64_t _index) const;
412
421 const uint64_t _index) const;
422
438 const OutputConfig &_config = OutputConfig::GlobalConfig()) const;
439
450 const std::string &_name) const;
451
456 public: bool AddLink(const Link &_link);
457
462 public: bool AddJoint(const Joint &_joint);
463
468 public: bool AddModel(const Model &_model);
469
474 public: bool AddFrame(const Frame &_frame);
475
477 public: void ClearLinks();
478
480 public: void ClearJoints();
481
483 public: void ClearModels();
484
486 public: void ClearFrames();
487
490 public: std::string Uri() const;
491
494 public: void SetUri(const std::string &_uri);
495
499 public: const sdf::Plugins &Plugins() const;
500
505
507 public: void ClearPlugins();
508
511 public: void AddPlugin(const Plugin &_plugin);
512
518 public: void ResolveAutoInertials(sdf::Errors &_errors,
519 const ParserConfig &_config);
520
526 private: void SetPoseRelativeToGraph(
528
534 private: void SetFrameAttachedToGraph(
536
539 private: const std::vector<std::pair<std::optional<sdf::NestedInclude>,
540 sdf::InterfaceModelConstPtr>> &MergedInterfaceModels() const;
541
545 private: bool IsMerged() const;
546
557 private: sdf::Frame PrepareForMerge(sdf::Errors &_errors,
558 const std::string &_parentOfProxyFrame);
559
563 friend class Root;
564 friend class World;
565
566 // Allow ModelWrapper from FrameSemantics.cc to call MergedInterfaceModels
567 friend struct ModelWrapper;
568
570 GZ_UTILS_IMPL_PTR(dataPtr)
571 };
572 }
573}
574#endif
A Frame element describes the properties associated with an explicit frame defined in a Model or Worl...
Definition Frame.hh:43
Definition Joint.hh:85
Definition Model.hh:57
sdf::ElementPtr Element() const
Get a pointer to the SDF element that was used during load.
bool AddModel(const Model &_model)
Add a model to the model.
bool AddJoint(const Joint &_joint)
Add a joint to the model.
void SetStatic(bool _static)
Set this model to be static or not static.
sdf::Plugins & Plugins()
Get a mutable vector of plugins attached to this object.
void ClearLinks()
Remove all links.
Joint * JointByName(const std::string &_name)
Get a mutable joint based on a name.
const Link * LinkByIndex(const uint64_t _index) const
Get an immediate (not nested) child link based on an index.
uint64_t ModelCount() const
Get the number of nested models that are immediate (not recursively nested) children of this Model ob...
const std::string & CanonicalLinkName() const
Get the name of the model's canonical link.
uint64_t LinkCount() const
Get the number of links that are immediate (not nested) children of this Model object.
void SetUri(const std::string &_uri)
Set the URI associated with this model.
const gz::math::Pose3d & RawPose() const
Get the pose of the model.
bool JointNameExists(const std::string &_name) const
Get whether a joint name exists.
bool AddLink(const Link &_link)
Add a link to the model.
void SetCanonicalLinkName(const std::string &_canonicalLink)
Set the name of the model's canonical link.
std::string Name() const
Get the name of the model.
void SetAllowAutoDisable(bool _allowAutoDisable)
Set this model to allow auto-disabling.
bool FrameNameExists(const std::string &_name) const
Get whether an explicit frame name exists.
Joint * JointByIndex(uint64_t _index)
Get an immediate (not nested) mutable child joint based on an index.
void AddPlugin(const Plugin &_plugin)
Add a plugin to this object.
std::string Uri() const
Get the URI associated with this model.
const Link * LinkByName(const std::string &_name) const
Get a link based on a name.
void ClearPlugins()
Remove all plugins.
const Frame * FrameByIndex(const uint64_t _index) const
Get an immediate (not nested) child explicit frame based on an index.
bool LinkNameExists(const std::string &_name) const
Get whether a link name exists.
Errors Load(sdf::ElementPtr _sdf, const ParserConfig &_config)
Load the model based on a element pointer.
void ResolveAutoInertials(sdf::Errors &_errors, const ParserConfig &_config)
Calculate and set the inertials for all the links belonging to the model object.
void ClearJoints()
Remove all joints.
Link * LinkByName(const std::string &_name)
Get a mutable link based on a name.
std::shared_ptr< const InterfaceModel > InterfaceModelByIndex(const uint64_t _index) const
Get an immediate (not recursively nested) child interface model based on an index.
bool Static() const
Check if this model should be static.
void SetPoseRelativeTo(const std::string &_frame)
Set the name of the coordinate frame relative to which this object's pose is expressed.
uint64_t InterfaceModelCount() const
Get the number of nested interface models that are immediate (not recursively nested) children of thi...
void SetSelfCollide(bool _selfCollide)
Set this model to self-collide or not self-collide.
const std::string & PlacementFrameName() const
Get the name of the placement frame of the model.
sdf::SemanticPose SemanticPose() const
Get SemanticPose object of this object to aid in resolving poses.
const sdf::Plugins & Plugins() const
Get the plugins attached to this object.
uint64_t FrameCount() const
Get the number of explicit frames that are immediate (not nested) children of this Model object.
Errors Load(ElementPtr _sdf)
Load the model based on a element pointer.
void ClearModels()
Remove all models.
bool SelfCollide() const
Check if this model should self-collide.
void ClearFrames()
Remove all frames.
void SetEnableWind(bool _enableWind)
Set whether this model should be subject to wind.
const Link * CanonicalLink() const
Get the model's canonical link.
bool EnableWind() const
Check if this model should be subject to wind.
uint64_t JointCount() const
Get the number of joints that are immediate (not nested) children of this Model object.
Model * ModelByName(const std::string &_name)
Get a mutable nested model based on a name.
const Frame * FrameByName(const std::string &_name) const
Get an explicit frame based on a name.
const Joint * JointByName(const std::string &_name) const
Get a joint based on a name.
bool NameExistsInFrameAttachedToGraph(const std::string &_name) const
Check if a given name exists in the FrameAttachedTo graph at the scope of the model.
bool AllowAutoDisable() const
Check if this model should be allowed to auto-disable.
const Model * ModelByName(const std::string &_name) const
Get a nested model based on a name.
bool ModelNameExists(const std::string &_name) const
Get whether a nested model name exists.
Frame * FrameByIndex(uint64_t _index)
Get a mutable immediate (not nested) child explicit frame based on an index.
void SetRawPose(const gz::math::Pose3d &_pose)
Set the pose of the model.
Model()
Default constructor.
void SetPlacementFrameName(const std::string &_name)
Set the name of the placement frame of the model.
Frame * FrameByName(const std::string &_name)
Get a mutable explicit frame based on a name.
Link * LinkByIndex(uint64_t _index)
Get an immediate (not nested) mutable child link based on an index.
const Joint * JointByIndex(const uint64_t _index) const
Get an immediate (not nested) child joint based on an index.
const Model * ModelByIndex(const uint64_t _index) const
Get an immediate (not recursively nested) child model based on an index.
std::pair< const Link *, std::string > CanonicalLinkAndRelativeName() const
Get the model's canonical link and the nested name of the link relative to the current model,...
sdf::ElementPtr ToElement(const OutputConfig &_config=OutputConfig::GlobalConfig()) const
Create and return an SDF element filled with data from this model.
void SetName(const std::string &_name)
Set the name of the model.
Model * ModelByIndex(uint64_t _index)
Get an immediate (not recursively nested) mutable child model.
const NestedInclude * InterfaceModelNestedIncludeByIndex(const uint64_t _index) const
Get the nested include information of an immediate (not recursively nested) child interface model bas...
bool AddFrame(const Frame &_frame)
Add a frame to the model.
Errors ValidateGraphs() const
Check that the FrameAttachedToGraph and PoseRelativeToGraph are valid.
const std::string & PoseRelativeTo() const
Get the name of the coordinate frame relative to which this object's pose is expressed.
Contains the necessary information about an included model file for custom model parsers to be able t...
Definition InterfaceElements.hh:48
This class contains configuration options for SDF output.
Definition OutputConfig.hh:59
This class contains configuration options for the libsdformat parser.
Definition ParserConfig.hh:121
Definition Plugin.hh:46
Root class that acts as an entry point to the SDF document model.
Definition Root.hh:58
Definition Collision.hh:44
SemanticPose is a data structure that can be used by different DOM objects to resolve poses on a Pose...
Definition SemanticPose.hh:55
Definition World.hh:59
std::shared_ptr< const InterfaceModel > InterfaceModelConstPtr
Definition InterfaceModel.hh:51
std::vector< Plugin > Plugins
A vector of Plugin.
Definition Plugin.hh:245
std::vector< Error > Errors
A vector of Error.
Definition Types.hh:80
std::shared_ptr< Element > ElementPtr
Definition Element.hh:55
namespace for Simulation Description Format parser
Definition Actor.hh:35
#define SDFORMAT_VISIBLE
Use to represent "symbol visible" if supported.
Definition system_util.hh:25