Parameters related to the axis of rotation for rotational joints, and the axis of translation for prismatic joints. More...
#include <JointAxis.hh>
Public Member Functions | |
JointAxis () | |
Default constructor. More... | |
double | Damping () const |
Get the physical velocity dependent viscous damping coefficient of the joint axis. More... | |
double | Dissipation () const |
Get the joint stop dissipation. More... | |
double | Effort () const |
Get the value for enforcing the maximum absolute joint effort that can be applied. More... | |
sdf::ElementPtr | Element () const |
Get a pointer to the SDF element that was used during load. More... | |
double | Friction () const |
Get the physical static friction value of the joint. More... | |
Errors | Load (ElementPtr _sdf) |
Load the joint axis based on a element pointer. More... | |
double | Lower () const |
Get the lower joint axis limit (radians for revolute joints, meters for prismatic joints). More... | |
double | MaxVelocity () const |
Get the value for enforcing the maximum absolute joint velocity. More... | |
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. More... | |
void | SetDamping (const double _damping) |
Set the physical velocity dependent viscous damping coefficient of the joint axis. More... | |
void | SetDissipation (const double _dissipation) |
Set the joint stop dissipation. More... | |
void | SetEffort (double _effort) |
Set the value for enforcing the maximum absolute joint effort that can be applied. More... | |
void | SetFriction (const double _friction) |
Set the physical static friction value of the joint. More... | |
void | SetLower (const double _lower) |
Set the lower joint axis limit (radians for revolute joints, meters for prismatic joints). More... | |
void | SetMaxVelocity (const double _velocity) |
Set the value for enforcing the maximum absolute joint velocity. More... | |
void | SetSpringReference (const double _spring) |
Set the spring reference position for this joint axis. More... | |
void | SetSpringStiffness (const double _spring) |
Set the spring stiffness for this joint axis. More... | |
void | SetStiffness (const double _stiffness) |
Get the joint stop stiffness. More... | |
void | SetUpper (const double _upper) |
Set the upper joint axis limit (radians for revolute joints, meters for prismatic joints). More... | |
sdf::Errors | SetXyz (const gz::math::Vector3d &_xyz) |
Set the x,y,z components of the axis unit vector. More... | |
void | SetXyzExpressedIn (const std::string &_frame) |
Set the name of the coordinate frame in which this joint axis's unit vector is expressed. More... | |
double | SpringReference () const |
Get the spring reference position for this joint axis. More... | |
double | SpringStiffness () const |
Get the spring stiffness for this joint axis. More... | |
double | Stiffness () const |
Get the joint stop stiffness. More... | |
sdf::ElementPtr | ToElement (sdf::Errors &_errors, unsigned int _index=0u) const |
Create and return an SDF element filled with data from this joint axis. More... | |
sdf::ElementPtr | ToElement (unsigned int _index=0u) const |
Create and return an SDF element filled with data from this joint axis. More... | |
double | Upper () const |
Get the upper joint axis limit (radians for revolute joints, meters for prismatic joints). More... | |
gz::math::Vector3d | Xyz () const |
Get the x,y,z components of the axis unit vector. More... | |
const std::string & | XyzExpressedIn () const |
Get the name of the coordinate frame in which this joint axis's unit vector is expressed. More... | |
Parameters related to the axis of rotation for rotational joints, and the axis of translation for prismatic joints.
sdf::SDF_VERSION_NAMESPACE::JointAxis::JointAxis | ( | ) |
Default constructor.
double sdf::SDF_VERSION_NAMESPACE::JointAxis::Damping | ( | ) | const |
Get the physical velocity dependent viscous damping coefficient of the joint axis.
The default value is zero (0.0).
double sdf::SDF_VERSION_NAMESPACE::JointAxis::Dissipation | ( | ) | const |
Get the joint stop dissipation.
The default value is 1.0.
double sdf::SDF_VERSION_NAMESPACE::JointAxis::Effort | ( | ) | const |
Get the value for enforcing the maximum absolute joint effort that can be applied.
The limit is not enforced if the value is infinity. The default value is infinity.
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::JointAxis::Element | ( | ) | const |
double sdf::SDF_VERSION_NAMESPACE::JointAxis::Friction | ( | ) | const |
Get the physical static friction value of the joint.
The default value is zero (0.0).
Errors sdf::SDF_VERSION_NAMESPACE::JointAxis::Load | ( | ElementPtr | _sdf | ) |
double sdf::SDF_VERSION_NAMESPACE::JointAxis::Lower | ( | ) | const |
Get the lower joint axis limit (radians for revolute joints, meters for prismatic joints).
Not valid if the joint that uses this axis is continuous. The default value is -1e16.
double sdf::SDF_VERSION_NAMESPACE::JointAxis::MaxVelocity | ( | ) | const |
Get the value for enforcing the maximum absolute joint velocity.
The default value is infinity.
Errors sdf::SDF_VERSION_NAMESPACE::JointAxis::ResolveXyz | ( | gz::math::Vector3d & | _xyz, |
const std::string & | _resolveTo = "" |
||
) | const |
Express xyz unit vector of this axis in the coordinates of another named frame.
[out] | _xyz | Resolved unit vector. |
[in] | _resolveTo | Name of frame in whose coordinates this object should be resolved. If unset, it is resolved in the coordinates of its xml parent object, which is always a joint frame. |
void sdf::SDF_VERSION_NAMESPACE::JointAxis::SetDamping | ( | const double | _damping | ) |
Set the physical velocity dependent viscous damping coefficient of the joint axis.
[in] | _damping | The physical velocity dependent viscous damping coefficient of the joint axis |
void sdf::SDF_VERSION_NAMESPACE::JointAxis::SetDissipation | ( | const double | _dissipation | ) |
Set the joint stop dissipation.
[in] | _dissipation | The joint stop dissipation. |
void sdf::SDF_VERSION_NAMESPACE::JointAxis::SetEffort | ( | double | _effort | ) |
Set the value for enforcing the maximum absolute joint effort that can be applied.
The limit is not enforced if the value is infinity.
[in] | _effort | Symmetric effort limit. |
void sdf::SDF_VERSION_NAMESPACE::JointAxis::SetFriction | ( | const double | _friction | ) |
Set the physical static friction value of the joint.
[in] | _friction | The physical static friction value of the joint. |
void sdf::SDF_VERSION_NAMESPACE::JointAxis::SetLower | ( | const double | _lower | ) |
Set the lower joint axis limit (radians for revolute joints, meters for prismatic joints).
Not valid if the joint that uses this axis is continuous.
[in] | _lower | The lower joint axis limit |
void sdf::SDF_VERSION_NAMESPACE::JointAxis::SetMaxVelocity | ( | const double | _velocity | ) |
Set the value for enforcing the maximum absolute joint velocity.
[in] | _velocity | The value for enforcing the maximum absolute joint velocity. |
void sdf::SDF_VERSION_NAMESPACE::JointAxis::SetSpringReference | ( | const double | _spring | ) |
Set the spring reference position for this joint axis.
[in] | _spring | The spring reference position for this joint axis. |
void sdf::SDF_VERSION_NAMESPACE::JointAxis::SetSpringStiffness | ( | const double | _spring | ) |
Set the spring stiffness for this joint axis.
[in] | _spring | The spring stiffness for this joint axis. |
void sdf::SDF_VERSION_NAMESPACE::JointAxis::SetStiffness | ( | const double | _stiffness | ) |
Get the joint stop stiffness.
[in] | _stiffness | The joint stop stiffness. |
void sdf::SDF_VERSION_NAMESPACE::JointAxis::SetUpper | ( | const double | _upper | ) |
Set the upper joint axis limit (radians for revolute joints, meters for prismatic joints).
Not valid if joint that uses this axis is continuous.
[in] | _upper | The upper joint axis limit. |
sdf::Errors sdf::SDF_VERSION_NAMESPACE::JointAxis::SetXyz | ( | const gz::math::Vector3d & | _xyz | ) |
Set the x,y,z components of the axis unit vector.
[in] | _xyz | The x,y,z components of the axis unit vector. |
void sdf::SDF_VERSION_NAMESPACE::JointAxis::SetXyzExpressedIn | ( | const std::string & | _frame | ) |
Set the name of the coordinate frame in which this joint axis's unit vector is expressed.
An empty value implies the parent (joint) frame.
[in] | The | name of the xyz expressed-in frame. |
double sdf::SDF_VERSION_NAMESPACE::JointAxis::SpringReference | ( | ) | const |
Get the spring reference position for this joint axis.
The default value is zero (0.0).
double sdf::SDF_VERSION_NAMESPACE::JointAxis::SpringStiffness | ( | ) | const |
Get the spring stiffness for this joint axis.
The default value is zero (0.0).
double sdf::SDF_VERSION_NAMESPACE::JointAxis::Stiffness | ( | ) | const |
Get the joint stop stiffness.
The default value is 1e8.
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::JointAxis::ToElement | ( | sdf::Errors & | _errors, |
unsigned int | _index = 0u |
||
) | const |
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::JointAxis::ToElement | ( | unsigned int | _index = 0u | ) | const |
double sdf::SDF_VERSION_NAMESPACE::JointAxis::Upper | ( | ) | const |
Get the upper joint axis limit (radians for revolute joints, meters for prismatic joints).
Not valid if joint that uses this axis is continuous. The default value is 1e16.
gz::math::Vector3d sdf::SDF_VERSION_NAMESPACE::JointAxis::Xyz | ( | ) | const |
Get the x,y,z components of the axis unit vector.
The axis is expressed in the frame named in XyzExpressedIn() and defaults to the joint frame if that method returns an empty string. The vector should be normalized. The default value is gz::math::Vector3d::UnitZ which equals (0, 0, 1).
const std::string& sdf::SDF_VERSION_NAMESPACE::JointAxis::XyzExpressedIn | ( | ) | const |
Get the name of the coordinate frame in which this joint axis's unit vector is expressed.
An empty value implies the parent (joint) frame.