Loading...
Searching...
No Matches
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 <string>
21#include <gz/math/Pose3.hh>
22#include <gz/utils/ImplPtr.hh>
23#include "sdf/Element.hh"
24#include "sdf/SemanticPose.hh"
25#include "sdf/Types.hh"
26#include "sdf/config.hh"
27#include "sdf/system_util.hh"
28
29namespace sdf
30{
31 // Inline bracket to help doxygen filtering.
32 inline namespace SDF_VERSION_NAMESPACE {
33 //
34
35 // Forward declarations.
36 class JointAxis;
37 struct FrameAttachedToGraph;
38 struct PoseRelativeToGraph;
39 template <typename T> class ScopedGraph;
40 class Sensor;
41
45 enum class JointType
46 {
49 INVALID = 0,
50
52 BALL = 1,
53
56 CONTINUOUS = 2,
57
60 FIXED = 3,
61
63 GEARBOX = 4,
64
67 PRISMATIC = 5,
68
71 REVOLUTE = 6,
72
74 REVOLUTE2 = 7,
75
78 SCREW = 8,
79
81 UNIVERSAL = 9
82 };
83
85 {
87 public: Joint();
88
95 public: Errors Load(ElementPtr _sdf);
96
100 public: const std::string &Name() const;
101
105 public: void SetName(const std::string &_name);
106
109 public: JointType Type() const;
110
113 public: void SetType(const JointType _jointType);
114
117 public: const std::string &ParentName() const;
118
121 public: void SetParentName(const std::string &_name);
122
125 public: const std::string &ChildName() const;
126
129 public: void SetChildName(const std::string &_name);
130
135 public: Errors ResolveChildLink(std::string &_link) const;
136
141 public: Errors ResolveParentLink(std::string &_link) const;
142
151 public: const JointAxis *Axis(const unsigned int _index = 0) const;
152
159 public: void SetAxis(const unsigned int _index, const JointAxis &_axis);
160
166 public: const gz::math::Pose3d &RawPose() const;
167
171 public: void SetRawPose(const gz::math::Pose3d &_pose);
172
177 public: const std::string &PoseRelativeTo() const;
178
183 public: void SetPoseRelativeTo(const std::string &_frame);
184
189 public: double ScrewThreadPitch() const;
190
194 public: void SetScrewThreadPitch(double _threadPitch);
195
200 public: double ThreadPitch() const;
201
206 public: void SetThreadPitch(double _threadPitch);
207
212 public: sdf::ElementPtr Element() const;
213
218
221 public: uint64_t SensorCount() const;
222
228 public: const Sensor *SensorByIndex(const uint64_t _index) const;
229
235 public: Sensor *SensorByIndex(uint64_t _index);
236
240 public: bool SensorNameExists(const std::string &_name) const;
241
247 public: const Sensor *SensorByName(const std::string &_name) const;
248
254 public: Sensor *SensorByName(const std::string &_name);
255
261 public: sdf::ElementPtr ToElement() const;
262
267 public: bool AddSensor(const Sensor &_sensor);
268
270 public: void ClearSensors();
271
276 private: void SetFrameAttachedToGraph(
278
282 private: void SetPoseRelativeToGraph(
284
286 friend class Model;
287
289 friend class World;
290
292 GZ_UTILS_IMPL_PTR(dataPtr)
293 };
294 }
295}
296#endif
Parameters related to the axis of rotation for rotational joints, and the axis of translation for pri...
Definition JointAxis.hh:121
Definition Joint.hh:85
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.
double ScrewThreadPitch() const
Get the displacement along the joint axis for each complete revolution around the joint axis (only va...
const Sensor * SensorByName(const std::string &_name) const
Get a sensor based on a name.
void SetScrewThreadPitch(double _threadPitch)
Set the thread pitch (only valid for screw joints).
const Sensor * SensorByIndex(const uint64_t _index) const
Get a sensor based on an index.
sdf::ElementPtr ToElement() const
Create and return an SDF element filled with data from this joint.
double ThreadPitch() const
Get the thread pitch in gazebo-classic format (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.
const std::string & ChildName() const
Get the name of this joint's child frame.
void SetThreadPitch(double _threadPitch)
Set the thread pitch in gazebo-classic format (only valid for screw joints).
void SetChildName(const std::string &_name)
Set the name of the child frame.
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.
void SetParentName(const std::string &_name)
Set the name of the parent frame.
JointType Type() const
Get the joint type.
const std::string & ParentName() const
Get the name of this joint's parent frame.
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:57
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 World.hh:59
JointType
The set of joint types.
Definition Joint.hh:46
@ REVOLUTE
A hinge joint that rotates on a single axis with a fixed range of motion.
@ BALL
A ball and socket joint.
@ SCREW
A single degree of freedom joint with coupled sliding and rotational motion.
@ REVOLUTE2
Same as two revolute joints connected in series.
@ GEARBOX
Geared revolute joint.
@ PRISMATIC
A sliding joint that slides along an axis with a limited range specified by upper and lower limits.
@ UNIVERSAL
Similar to a ball joint, but constrains one degree of freedom.
@ CONTINUOUS
A hinge joint that rotates on a single axis with a continuous range of motion.
@ FIXED
A joint with zero degrees of freedom that rigidly connects two links.
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