Joint.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_JOINT_HH_
18 #define SDF_JOINT_HH_
19 
20 #include <memory>
21 #include <string>
22 #include <gz/math/Pose3.hh>
23 #include "sdf/Element.hh"
24 #include "sdf/SemanticPose.hh"
25 #include "sdf/Types.hh"
26 #include "sdf/sdf_config.h"
27 #include "sdf/system_util.hh"
28 
29 namespace sdf
30 {
31  // Inline bracket to help doxygen filtering.
32  inline namespace SDF_VERSION_NAMESPACE {
33  //
34 
35  // Forward declarations.
36  class JointAxis;
37  class JointPrivate;
38  struct PoseRelativeToGraph;
39  class Sensor;
40 
44  enum class JointType
45  {
48  INVALID = 0,
49 
51  BALL = 1,
52 
55  CONTINUOUS = 2,
56 
59  FIXED = 3,
60 
62  GEARBOX = 4,
63 
66  PRISMATIC = 5,
67 
70  REVOLUTE = 6,
71 
73  REVOLUTE2 = 7,
74 
77  SCREW = 8,
78 
80  UNIVERSAL = 9
81  };
82 
84  {
86  public: Joint();
87 
90  public: Joint(const Joint &_joint);
91 
94  public: Joint(Joint &&_joint) noexcept;
95 
99  public: Joint &operator=(Joint &&_joint);
100 
104  public: Joint &operator=(const Joint &_joint);
105 
107  public: ~Joint();
108 
115  public: Errors Load(ElementPtr _sdf);
116 
120  public: const std::string &Name() const;
121 
125  public: void SetName(const std::string &_name);
126 
129  public: JointType Type() const;
130 
133  public: void SetType(const JointType _jointType);
134 
137  public: const std::string &ParentLinkName() const;
138 
141  public: void SetParentLinkName(const std::string &_name);
142 
145  public: const std::string &ChildLinkName() const;
146 
149  public: void SetChildLinkName(const std::string &_name);
150 
159  public: const JointAxis *Axis(const unsigned int _index = 0) const;
160 
167  public: void SetAxis(const unsigned int _index, const JointAxis &_axis);
168 
175  public: const gz::math::Pose3d &Pose() const
176  SDF_DEPRECATED(9.0);
177 
182  public: void SetPose(const gz::math::Pose3d &_pose)
183  SDF_DEPRECATED(9.0);
184 
190  public: const gz::math::Pose3d &RawPose() const;
191 
195  public: void SetRawPose(const gz::math::Pose3d &_pose);
196 
201  public: const std::string &PoseRelativeTo() const;
202 
207  public: void SetPoseRelativeTo(const std::string &_frame);
208 
214  public: const std::string &PoseFrame() const
215  SDF_DEPRECATED(9.0);
216 
222  public: void SetPoseFrame(const std::string &_frame)
223  SDF_DEPRECATED(9.0);
224 
227  public: double ThreadPitch() const;
228 
231  public: void SetThreadPitch(double _threadPitch);
232 
237  public: sdf::ElementPtr Element() const;
238 
242  public: sdf::SemanticPose SemanticPose() const;
243 
246  public: uint64_t SensorCount() const;
247 
253  public: const Sensor *SensorByIndex(const uint64_t _index) const;
254 
258  public: bool SensorNameExists(const std::string &_name) const;
259 
265  public: const Sensor *SensorByName(const std::string &_name) const;
266 
271  private: void SetPoseRelativeToGraph(
272  std::weak_ptr<const PoseRelativeToGraph> _graph);
273 
275  friend class Model;
276 
278  private: JointPrivate *dataPtr = nullptr;
279  };
280  }
281 }
282 #endif
sdf::v9::JointType
JointType
Definition: Joint.hh:44
sdf::v9::JointAxis
Parameters related to the axis of rotation for rotational joints, and the axis of translation for pri...
Definition: JointAxis.hh:40
sdf::v9::JointType::GEARBOX
@ GEARBOX
Geared revolute joint.
sdf::v9::JointType::REVOLUTE2
@ REVOLUTE2
Same as two revolute joints connected in series.
sdf
namespace for Simulation Description Format parser
Definition: Actor.hh:32
Types.hh
SemanticPose.hh
sdf::v9::Errors
std::vector< Error > Errors
A vector of Error.
Definition: Types.hh:89
sdf::v9::JointType::CONTINUOUS
@ CONTINUOUS
A hinge joint that rotates on a single axis with a continuous range of motion.
SDFORMAT_VISIBLE
#define SDFORMAT_VISIBLE
Definition: system_util.hh:48
sdf::v9::JointType::SCREW
@ SCREW
A single degree of freedom joint with coupled sliding and rotational motion.
sdf::v9::Joint
Definition: Joint.hh:83
sdf::v9::JointType::BALL
@ BALL
A ball and socket joint.
sdf::v9::SDF_DEPRECATED
class SDFORMAT_VISIBLE SDF_DEPRECATED(9.2) URDF2SDF
URDF to SDF converter.
Definition: parser_urdf.hh:40
sdf::v9::SemanticPose
SemanticPose is a data structure that can be used by different DOM objects to resolve poses on a Pose...
Definition: SemanticPose.hh:53
sdf::v9::JointType::REVOLUTE
@ REVOLUTE
A hinge joint that rotates on a single axis with a fixed range of motion.
sdf::v9::JointType::UNIVERSAL
@ UNIVERSAL
Similar to a ball joint, but constrains one degree of freedom.
sdf::v9::ElementPtr
std::shared_ptr< Element > ElementPtr
Definition: Element.hh:53
sdf::v9::Model
Definition: Model.hh:43
sdf::v9::JointType::FIXED
@ FIXED
A joint with zero degrees of freedom that rigidly connects two links.
system_util.hh
sdf::v9::Element
class SDFORMAT_VISIBLE Element
Definition: Element.hh:49
sdf::SDF_VERSION_NAMESPACE::Sensor
Information about an SDF sensor.
Definition: Sensor.hh:121
sdf::v9::ForceTorqueFrame::INVALID
@ INVALID
Invalid frame.
Element.hh
sdf::v9::JointType::PRISMATIC
@ PRISMATIC
A sliding joint that slides along an axis with a limited range specified by upper and lower limits.