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 <gz/utils/ImplPtr.hh>
24#include "sdf/Element.hh"
25#include "sdf/SemanticPose.hh"
26#include "sdf/Types.hh"
27#include "sdf/sdf_config.h"
28#include "sdf/system_util.hh"
29
30namespace sdf
31{
32 // Inline bracket to help doxygen filtering.
33 inline namespace SDF_VERSION_NAMESPACE {
34 //
35
36 // Forward declarations.
37 class JointAxis;
38 struct FrameAttachedToGraph;
39 struct PoseRelativeToGraph;
40 template <typename T> class ScopedGraph;
41 class Sensor;
42
46 enum class JointType
47 {
50 INVALID = 0,
51
53 BALL = 1,
54
57 CONTINUOUS = 2,
58
61 FIXED = 3,
62
64 GEARBOX = 4,
65
68 PRISMATIC = 5,
69
72 REVOLUTE = 6,
73
75 REVOLUTE2 = 7,
76
79 SCREW = 8,
80
82 UNIVERSAL = 9
83 };
84
86 {
88 public: Joint();
89
96 public: Errors Load(ElementPtr _sdf);
97
101 public: const std::string &Name() const;
102
106 public: void SetName(const std::string &_name);
107
110 public: JointType Type() const;
111
114 public: void SetType(const JointType _jointType);
115
118 public: const std::string &ParentLinkName() const;
119
122 public: void SetParentLinkName(const std::string &_name);
123
126 public: const std::string &ChildLinkName() const;
127
130 public: void SetChildLinkName(const std::string &_name);
131
136 public: Errors ResolveChildLink(std::string &_link) const;
137
142 public: Errors ResolveParentLink(std::string &_link) const;
143
152 public: const JointAxis *Axis(const unsigned int _index = 0) const;
153
160 public: void SetAxis(const unsigned int _index, const JointAxis &_axis);
161
167 public: const gz::math::Pose3d &RawPose() const;
168
172 public: void SetRawPose(const gz::math::Pose3d &_pose);
173
178 public: const std::string &PoseRelativeTo() const;
179
184 public: void SetPoseRelativeTo(const std::string &_frame);
185
188 public: double ThreadPitch() const;
189
192 public: void SetThreadPitch(double _threadPitch);
193
198 public: sdf::ElementPtr Element() const;
199
204
207 public: uint64_t SensorCount() const;
208
214 public: const Sensor *SensorByIndex(const uint64_t _index) const;
215
221 public: Sensor *SensorByIndex(uint64_t _index);
222
226 public: bool SensorNameExists(const std::string &_name) const;
227
233 public: const Sensor *SensorByName(const std::string &_name) const;
234
240 public: Sensor *SensorByName(const std::string &_name);
241
247 public: sdf::ElementPtr ToElement() const;
248
253 public: bool AddSensor(const Sensor &_sensor);
254
256 public: void ClearSensors();
257
262 private: void SetFrameAttachedToGraph(
264
268 private: void SetPoseRelativeToGraph(
270
272 friend class Model;
273
275 IGN_UTILS_IMPL_PTR(dataPtr)
276 };
277 }
278}
279#endif
Parameters related to the axis of rotation for rotational joints, and the axis of translation for pri...
Definition: JointAxis.hh:43
Definition: Joint.hh:86
void SetRawPose(const gz::math::Pose3d &_pose)
Set the pose of the joint.
bool AddSensor(const Sensor &_sensor)
Add a sensors to the joint.
const std::string & Name() const
Get the name of the joint.
const Sensor * SensorByName(const std::string &_name) const
Get a sensor based on a name.
const std::string & ParentLinkName() const
Get the name of this joint's parent link.
const Sensor * SensorByIndex(const uint64_t _index) const
Get a sensor based on an index.
void SetChildLinkName(const std::string &_name)
Set the name of the child link.
sdf::ElementPtr ToElement() const
Create and return an SDF element filled with data from this joint.
double ThreadPitch() const
Get the thread pitch (only valid for screw joints)
Errors ResolveChildLink(std::string &_link) const
Resolve the name of the child link from the FrameAttachedToGraph.
const std::string & PoseRelativeTo() const
Get the name of the coordinate frame relative to which this object's pose is expressed.
void SetThreadPitch(double _threadPitch)
Set the thread pitch (only valid for screw joints)
void SetPoseRelativeTo(const std::string &_frame)
Set the name of the coordinate frame relative to which this object's pose is expressed.
void ClearSensors()
Remove all sensors.
sdf::SemanticPose SemanticPose() const
Get SemanticPose object of this object to aid in resolving poses.
Errors ResolveParentLink(std::string &_link) const
Resolve the name of the parent link from the FrameAttachedToGraph.
sdf::ElementPtr Element() const
Get a pointer to the SDF element that was used during load.
void SetType(const JointType _jointType)
Set the joint type.
Sensor * SensorByIndex(uint64_t _index)
Get a mutable sensor based on an index.
bool SensorNameExists(const std::string &_name) const
Get whether a sensor name exists.
void SetName(const std::string &_name)
Set the name of the joint.
JointType Type() const
Get the joint type.
void SetParentLinkName(const std::string &_name)
Set the name of the parent link.
const std::string & ChildLinkName() const
Get the name of this joint's child link.
Joint()
Default constructor.
void SetAxis(const unsigned int _index, const JointAxis &_axis)
Set a joint axis.
const JointAxis * Axis(const unsigned int _index=0) const
Get a joint axis.
const gz::math::Pose3d & RawPose() const
Get the pose of the joint.
uint64_t SensorCount() const
Get the number of sensors.
Sensor * SensorByName(const std::string &_name)
Get a mutable sensor based on a name.
Errors Load(ElementPtr _sdf)
Load the joint based on a element pointer.
Definition: Model.hh:55
Definition: Collision.hh:39
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:137
JointType
The set of joint types.
Definition: Joint.hh:47
std::vector< Error > Errors
A vector of Error.
Definition: Types.hh:106
std::shared_ptr< Element > ElementPtr
Definition: Element.hh:54
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