Link.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_LINK_HH_
18 #define SDF_LINK_HH_
19 
20 #include <memory>
21 #include <optional>
22 #include <string>
23 #include <gz/math/Inertial.hh>
24 #include <gz/math/Pose3.hh>
25 #include <gz/utils/ImplPtr.hh>
26 #include "sdf/Element.hh"
27 #include "sdf/SemanticPose.hh"
28 #include "sdf/Types.hh"
29 #include "sdf/sdf_config.h"
30 #include "sdf/system_util.hh"
31 #include "sdf/ParserConfig.hh"
32 #include "sdf/Error.hh"
33 
34 namespace sdf
35 {
36  // Inline bracket to help doxygen filtering.
37  inline namespace SDF_VERSION_NAMESPACE {
38  //
39 
40  // Forward declarations.
41  class Collision;
42  class Light;
43  class ParserConfig;
44  class ParticleEmitter;
45  class Projector;
46  class Sensor;
47  class Visual;
48  struct PoseRelativeToGraph;
49  template <typename T> class ScopedGraph;
50 
52  {
54  public: Link();
55 
62  public: Errors Load(ElementPtr _sdf);
63 
71  public: Errors Load(ElementPtr _sdf, const ParserConfig &_config);
72 
76  public: std::string Name() const;
77 
81  public: void SetName(const std::string &_name);
82 
86  public: std::optional<double> Density() const;
87 
90  public: void SetDensity(double _density);
91 
97 
102  public: void SetAutoInertiaParams(const sdf::ElementPtr _autoInertiaParams);
103 
106  public: uint64_t VisualCount() const;
107 
113  public: const Visual *VisualByIndex(const uint64_t _index) const;
114 
120  public: Visual *VisualByIndex(uint64_t _index);
121 
125  public: bool VisualNameExists(const std::string &_name) const;
126 
130  public: const Visual *VisualByName(const std::string &_name) const;
131 
135  public: Visual *VisualByName(const std::string &_name);
136 
139  public: uint64_t CollisionCount() const;
140 
146  public: const Collision *CollisionByIndex(const uint64_t _index) const;
147 
153  public: Collision *CollisionByIndex(uint64_t _index);
154 
158  public: bool CollisionNameExists(const std::string &_name) const;
159 
163  public: const Collision *CollisionByName(const std::string &_name) const;
164 
168  public: Collision *CollisionByName(const std::string &_name);
169 
172  public: uint64_t LightCount() const;
173 
179  public: const Light *LightByIndex(const uint64_t _index) const;
180 
186  public: Light *LightByIndex(uint64_t _index);
187 
191  public: bool LightNameExists(const std::string &_name) const;
192 
196  public: const Light *LightByName(const std::string &_name) const;
197 
201  public: Light *LightByName(const std::string &_name);
202 
205  public: uint64_t SensorCount() const;
206 
212  public: const Sensor *SensorByIndex(const uint64_t _index) const;
213 
219  public: Sensor *SensorByIndex(uint64_t _index);
220 
224  public: bool SensorNameExists(const std::string &_name) const;
225 
231  public: const Sensor *SensorByName(const std::string &_name) const;
232 
238  public: Sensor *SensorByName(const std::string &_name);
239 
242  public: uint64_t ParticleEmitterCount() const;
243 
251  const uint64_t _index) const;
252 
259  public: ParticleEmitter *ParticleEmitterByIndex(uint64_t _index);
260 
264  public: bool ParticleEmitterNameExists(const std::string &_name) const;
265 
272  const std::string &_name) const;
273 
279  public: ParticleEmitter *ParticleEmitterByName(const std::string &_name);
280 
283  public: uint64_t ProjectorCount() const;
284 
291  public: const Projector *ProjectorByIndex(
292  const uint64_t _index) const;
293 
300  public: Projector *ProjectorByIndex(uint64_t _index);
301 
305  public: bool ProjectorNameExists(const std::string &_name) const;
306 
312  public: const Projector *ProjectorByName(
313  const std::string &_name) const;
314 
320  public: Projector *ProjectorByName(const std::string &_name);
321 
335  public: const gz::math::Inertiald &Inertial() const;
336 
341  public: bool SetInertial(const gz::math::Inertiald &_inertial);
342 
350  public: Errors ResolveInertial(gz::math::Inertiald &_inertial,
351  const std::string &_resolveTo = "") const;
352 
360  public: void ResolveAutoInertials(sdf::Errors &_errors,
361  const ParserConfig &_config);
362 
366  public: const gz::math::Pose3d &RawPose() const;
367 
371  public: void SetRawPose(const gz::math::Pose3d &_pose);
372 
377  public: const std::string &PoseRelativeTo() const;
378 
383  public: void SetPoseRelativeTo(const std::string &_frame);
384 
389  public: sdf::ElementPtr Element() const;
390 
395 
399  private: void SetPoseRelativeToGraph(
401 
403  friend class Model;
404 
409  public: bool EnableWind() const;
410 
414  public: bool EnableGravity() const;
415 
420  public: void SetEnableWind(bool _enableWind);
421 
425  public: void SetEnableGravity(bool _enableGravity);
426 
433  public: bool AutoInertia() const;
434 
438  public: void SetAutoInertia(bool _autoInertia);
439 
447  public: bool AutoInertiaSaved() const;
448 
451  public: void SetAutoInertiaSaved(bool _autoInertiaSaved);
452 
457  public: bool AddCollision(const Collision &_collision);
458 
463  public: bool AddVisual(const Visual &_visual);
464 
469  public: bool AddLight(const Light &_light);
470 
475  public: bool AddSensor(const Sensor &_sensor);
476 
481  public: bool AddParticleEmitter(const ParticleEmitter &_emitter);
482 
487  public: bool AddProjector(const Projector &_projector);
488 
490  public: void ClearCollisions();
491 
493  public: void ClearVisuals();
494 
496  public: void ClearLights();
497 
499  public: void ClearSensors();
500 
502  public: void ClearParticleEmitters();
503 
505  public: void ClearProjectors();
506 
512  public: sdf::ElementPtr ToElement() const;
513 
515  GZ_UTILS_IMPL_PTR(dataPtr)
516  };
517  }
518 }
519 #endif
A collision element descibes the collision properties associated with a link.
Definition: Collision.hh:51
Provides a description of a light source.
Definition: Light.hh:64
Definition: Model.hh:55
This class contains configuration options for the libsdformat parser.
Definition: ParserConfig.hh:100
A description of a particle emitter, which can be attached to a link.
Definition: ParticleEmitter.hh:61
A description of a projector, which can be attached to a link.
Definition: Projector.hh:44
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
Information about an SDF sensor.
Definition: Sensor.hh:141
Definition: Visual.hh:50
std::vector< Error > Errors
A vector of Error.
Definition: Types.hh:95
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