JointAxis.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_JOINTAXIS_HH_
18 #define SDF_JOINTAXIS_HH_
19 
20 #include <memory>
21 #include <string>
22 #include <utility>
23 #include <gz/math/Vector3.hh>
24 #include <gz/utils/ImplPtr.hh>
25 #include "sdf/Element.hh"
26 #include "sdf/Exception.hh"
27 #include "sdf/Types.hh"
28 #include "sdf/sdf_config.h"
29 #include "sdf/system_util.hh"
30 
31 namespace sdf
32 {
33  // Inline bracket to help doxygen filtering.
34  inline namespace SDF_VERSION_NAMESPACE {
35  //
36 
37  // Forward declare private data class.
38  struct PoseRelativeToGraph;
39  template <typename T> class ScopedGraph;
40 
50  {
61  public: MimicConstraint(
62  const std::string &_joint = "",
63  const std::string &_axis = "axis",
64  double _multiplier = 0.0,
65  double _offset = 0.0,
66  double _reference = 0.0);
67 
70  public: void SetJoint(const std::string &_joint);
71 
74  public: void SetAxis(const std::string &_axis);
75 
80  public: void SetMultiplier(double _multiplier);
81 
84  public: void SetOffset(double _offset);
85 
89  public: void SetReference(double _reference);
90 
93  public: const std::string &Joint() const;
94 
97  public: const std::string &Axis() const;
98 
103  public: double Multiplier() const;
104 
108  public: double Offset() const;
109 
113  public: double Reference() const;
114 
116  GZ_UTILS_IMPL_PTR(dataPtr)
117  };
118 
122  {
124  public: JointAxis();
125 
132  public: Errors Load(ElementPtr _sdf);
133 
142  public: gz::math::Vector3d Xyz() const;
143 
148  public: [[nodiscard]] sdf::Errors SetXyz(
149  const gz::math::Vector3d &_xyz);
150 
156  public: void SetMimic(const MimicConstraint &_mimic);
157 
163  public: std::optional<MimicConstraint> Mimic() const;
164 
170  public: double Damping() const;
171 
177  public: void SetDamping(const double _damping);
178 
183  public: double Friction() const;
184 
188  public: void SetFriction(const double _friction);
189 
194  public: double SpringReference() const;
195 
199  public: void SetSpringReference(const double _spring);
200 
205  public: double SpringStiffness() const;
206 
210  public: void SetSpringStiffness(const double _spring);
211 
217  public: double Lower() const;
218 
224  public: void SetLower(const double _lower);
225 
231  public: double Upper() const;
232 
238  public: void SetUpper(const double _upper);
239 
246  public: double Effort() const;
247 
253  public: void SetEffort(double _effort);
254 
259  public: double MaxVelocity() const;
260 
265  public: void SetMaxVelocity(const double _velocity);
266 
270  public: double Stiffness() const;
271 
276  public: void SetStiffness(const double _stiffness);
277 
281  public: double Dissipation() const;
282 
286  public: void SetDissipation(const double _dissipation);
287 
292  public: const std::string& XyzExpressedIn() const;
293 
298  public: void SetXyzExpressedIn(const std::string &_frame);
299 
308  gz::math::Vector3d &_xyz,
309  const std::string &_resolveTo = "") const;
310 
315  public: sdf::ElementPtr Element() const;
316 
323  public: sdf::ElementPtr ToElement(unsigned int _index = 0u) const;
324 
333  unsigned int _index = 0u) const;
334 
339  private: void SetXmlParentName(const std::string &_xmlParentName);
340 
345  private: void SetPoseRelativeToGraph(
347 
349  friend class Joint;
350 
352  GZ_UTILS_IMPL_PTR(dataPtr)
353  };
354  }
355 }
356 #endif
Parameters related to the axis of rotation for rotational joints, and the axis of translation for pri...
Definition: JointAxis.hh:122
sdf::ElementPtr Element() const
Get a pointer to the SDF element that was used during load.
void SetSpringReference(const double _spring)
Set the spring reference position for this joint axis.
Errors ResolveXyz(gz::math::Vector3d &_xyz, const std::string &_resolveTo="") const
Express xyz unit vector of this axis in the coordinates of another named frame.
double Damping() const
Get the physical velocity dependent viscous damping coefficient of the joint axis.
sdf::ElementPtr ToElement(sdf::Errors &_errors, unsigned int _index=0u) const
Create and return an SDF element filled with data from this joint axis.
void SetFriction(const double _friction)
Set the physical static friction value of the joint.
void SetXyzExpressedIn(const std::string &_frame)
Set the name of the coordinate frame in which this joint axis's unit vector is expressed.
void SetMimic(const MimicConstraint &_mimic)
Set the Mimic constraint parameters.
Errors Load(ElementPtr _sdf)
Load the joint axis based on a element pointer.
void SetStiffness(const double _stiffness)
Get the joint stop stiffness.
double Lower() const
Get the lower joint axis limit (radians for revolute joints, meters for prismatic joints).
void SetUpper(const double _upper)
Set the upper joint axis limit (radians for revolute joints, meters for prismatic joints).
void SetEffort(double _effort)
Set the value for enforcing the maximum absolute joint effort that can be applied.
std::optional< MimicConstraint > Mimic() const
Get the Mimic constraint parameters.
sdf::Errors SetXyz(const gz::math::Vector3d &_xyz)
Set the x,y,z components of the axis unit vector.
void SetDissipation(const double _dissipation)
Set the joint stop dissipation.
sdf::ElementPtr ToElement(unsigned int _index=0u) const
Create and return an SDF element filled with data from this joint axis.
void SetDamping(const double _damping)
Set the physical velocity dependent viscous damping coefficient of the joint axis.
double Effort() const
Get the value for enforcing the maximum absolute joint effort that can be applied.
double Dissipation() const
Get the joint stop dissipation.
double SpringReference() const
Get the spring reference position for this joint axis.
void SetLower(const double _lower)
Set the lower joint axis limit (radians for revolute joints, meters for prismatic joints).
void SetMaxVelocity(const double _velocity)
Set the value for enforcing the maximum absolute joint velocity.
gz::math::Vector3d Xyz() const
Get the x,y,z components of the axis unit vector.
double MaxVelocity() const
Get the value for enforcing the maximum absolute joint velocity.
void SetSpringStiffness(const double _spring)
Set the spring stiffness for this joint axis.
double Stiffness() const
Get the joint stop stiffness.
double Friction() const
Get the physical static friction value of the joint.
double SpringStiffness() const
Get the spring stiffness for this joint axis.
double Upper() const
Get the upper joint axis limit (radians for revolute joints, meters for prismatic joints).
const std::string & XyzExpressedIn() const
Get the name of the coordinate frame in which this joint axis's unit vector is expressed.
Definition: Joint.hh:86
Helper class to hold contents of a joint axis mimic tag, which define a Mimic constraint.
Definition: JointAxis.hh:50
double Offset() const
Retrieve the offset to the follower position in the linear constraint.
void SetMultiplier(double _multiplier)
Set the multiplier parameter, which represents the ratio between changes in the follower position rel...
void SetReference(double _reference)
Set the reference for the leader position before applying the multiplier in the linear constraint.
double Reference() const
Retrieve the reference for the leader position before applying the multiplier in the linear constrain...
const std::string & Joint() const
Retrieve the name of the leader joint.
void SetOffset(double _offset)
Set the offset to the follower position in the linear constraint.
void SetJoint(const std::string &_joint)
Set the leader joint name.
double Multiplier() const
Retrieve the multiplier parameter, which represents the ratio between changes in the follower positio...
void SetAxis(const std::string &_axis)
Set the leader axis name, either "axis" or "axis2".
const std::string & Axis() const
Retrieve the name of the leader axis, either "axis" or "axis2".
MimicConstraint(const std::string &_joint="", const std::string &_axis="axis", double _multiplier=0.0, double _offset=0.0, double _reference=0.0)
Constructor with arguments.
Definition: Collision.hh:44
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