#include <Joint.hh>
Public Member Functions | |
Joint () | |
Default constructor. More... | |
bool | AddSensor (const Sensor &_sensor) |
Add a sensors to the joint. More... | |
const JointAxis * | Axis (const unsigned int _index=0) const |
Get a joint axis. More... | |
const std::string & | ChildLinkName () const |
Get the name of this joint's child link. More... | |
void | ClearSensors () |
Remove all sensors. More... | |
sdf::ElementPtr | Element () const |
Get a pointer to the SDF element that was used during load. More... | |
Errors | Load (ElementPtr _sdf) |
Load the joint based on a element pointer. More... | |
const std::string & | Name () const |
Get the name of the joint. More... | |
const std::string & | ParentLinkName () const |
Get the name of this joint's parent link. More... | |
const std::string & | PoseRelativeTo () const |
Get the name of the coordinate frame relative to which this object's pose is expressed. More... | |
const gz::math::Pose3d & | RawPose () const |
Get the pose of the joint. More... | |
Errors | ResolveChildLink (std::string &_link) const |
Resolve the name of the child link from the FrameAttachedToGraph. More... | |
Errors | ResolveParentLink (std::string &_link) const |
Resolve the name of the parent link from the FrameAttachedToGraph. More... | |
sdf::SemanticPose | SemanticPose () const |
Get SemanticPose object of this object to aid in resolving poses. More... | |
const Sensor * | SensorByIndex (const uint64_t _index) const |
Get a sensor based on an index. More... | |
Sensor * | SensorByIndex (uint64_t _index) |
Get a mutable sensor based on an index. More... | |
Sensor * | SensorByName (const std::string &_name) |
Get a mutable sensor based on a name. More... | |
const Sensor * | SensorByName (const std::string &_name) const |
Get a sensor based on a name. More... | |
uint64_t | SensorCount () const |
Get the number of sensors. More... | |
bool | SensorNameExists (const std::string &_name) const |
Get whether a sensor name exists. More... | |
void | SetAxis (const unsigned int _index, const JointAxis &_axis) |
Set a joint axis. More... | |
void | SetChildLinkName (const std::string &_name) |
Set the name of the child link. More... | |
void | SetName (const std::string &_name) |
Set the name of the joint. More... | |
void | SetParentLinkName (const std::string &_name) |
Set the name of the parent link. More... | |
void | SetPoseRelativeTo (const std::string &_frame) |
Set the name of the coordinate frame relative to which this object's pose is expressed. More... | |
void | SetRawPose (const gz::math::Pose3d &_pose) |
Set the pose of the joint. More... | |
void | SetThreadPitch (double _threadPitch) |
Set the thread pitch (only valid for screw joints) More... | |
void | SetType (const JointType _jointType) |
Set the joint type. More... | |
double | ThreadPitch () const |
Get the thread pitch (only valid for screw joints) More... | |
sdf::ElementPtr | ToElement () const |
Create and return an SDF element filled with data from this joint. More... | |
JointType | Type () const |
Get the joint type. More... | |
sdf::SDF_VERSION_NAMESPACE::Joint::Joint | ( | ) |
Default constructor.
bool sdf::SDF_VERSION_NAMESPACE::Joint::AddSensor | ( | const Sensor & | _sensor | ) |
Add a sensors to the joint.
[in] | _sensor | Sensor to add. |
const JointAxis* sdf::SDF_VERSION_NAMESPACE::Joint::Axis | ( | const unsigned int | _index = 0 | ) | const |
Get a joint axis.
[in] | _index | This value specifies which axis to get. A value of zero corresponds to the first axis, which is the <axis> SDF element. Any other value will return the second axis, which is the <axis2> SDF element. |
const std::string& sdf::SDF_VERSION_NAMESPACE::Joint::ChildLinkName | ( | ) | const |
Get the name of this joint's child link.
void sdf::SDF_VERSION_NAMESPACE::Joint::ClearSensors | ( | ) |
Remove all sensors.
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Joint::Element | ( | ) | const |
Errors sdf::SDF_VERSION_NAMESPACE::Joint::Load | ( | ElementPtr | _sdf | ) |
const std::string& sdf::SDF_VERSION_NAMESPACE::Joint::Name | ( | ) | const |
Get the name of the joint.
The name of the joint must be unique within the scope of a Model.
const std::string& sdf::SDF_VERSION_NAMESPACE::Joint::ParentLinkName | ( | ) | const |
Get the name of this joint's parent link.
const std::string& sdf::SDF_VERSION_NAMESPACE::Joint::PoseRelativeTo | ( | ) | const |
Get the name of the coordinate frame relative to which this object's pose is expressed.
An empty value indicates that the frame is relative to the child link frame.
const gz::math::Pose3d& sdf::SDF_VERSION_NAMESPACE::Joint::RawPose | ( | ) | const |
Errors sdf::SDF_VERSION_NAMESPACE::Joint::ResolveChildLink | ( | std::string & | _link | ) | const |
Resolve the name of the child link from the FrameAttachedToGraph.
[out] | _body | Name of child link of this joint. |
Errors sdf::SDF_VERSION_NAMESPACE::Joint::ResolveParentLink | ( | std::string & | _link | ) | const |
Resolve the name of the parent link from the FrameAttachedToGraph.
It will return the name of a link or "world".
[out] | _body | Name of parent link of this joint. |
sdf::SemanticPose sdf::SDF_VERSION_NAMESPACE::Joint::SemanticPose | ( | ) | const |
Get SemanticPose object of this object to aid in resolving poses.
const Sensor* sdf::SDF_VERSION_NAMESPACE::Joint::SensorByIndex | ( | const uint64_t | _index | ) | const |
Get a sensor based on an index.
[in] | _index | Index of the sensor. The index should be in the range [0..SensorCount()). |
Sensor* sdf::SDF_VERSION_NAMESPACE::Joint::SensorByIndex | ( | uint64_t | _index | ) |
Get a mutable sensor based on an index.
[in] | _index | Index of the sensor. The index should be in the range [0..SensorCount()). |
Sensor* sdf::SDF_VERSION_NAMESPACE::Joint::SensorByName | ( | const std::string & | _name | ) |
Get a mutable sensor based on a name.
[in] | _name | Name of the sensor. |
const Sensor* sdf::SDF_VERSION_NAMESPACE::Joint::SensorByName | ( | const std::string & | _name | ) | const |
Get a sensor based on a name.
[in] | _name | Name of the sensor. |
uint64_t sdf::SDF_VERSION_NAMESPACE::Joint::SensorCount | ( | ) | const |
Get the number of sensors.
bool sdf::SDF_VERSION_NAMESPACE::Joint::SensorNameExists | ( | const std::string & | _name | ) | const |
Get whether a sensor name exists.
[in] | _name | Name of the sensor to check. |
void sdf::SDF_VERSION_NAMESPACE::Joint::SetAxis | ( | const unsigned int | _index, |
const JointAxis & | _axis | ||
) |
void sdf::SDF_VERSION_NAMESPACE::Joint::SetChildLinkName | ( | const std::string & | _name | ) |
Set the name of the child link.
[in] | _name | Name of the child link. |
void sdf::SDF_VERSION_NAMESPACE::Joint::SetName | ( | const std::string & | _name | ) |
Set the name of the joint.
The name of the joint must be unique within the scope of a Model.
[in] | _name | Name of the joint. |
void sdf::SDF_VERSION_NAMESPACE::Joint::SetParentLinkName | ( | const std::string & | _name | ) |
Set the name of the parent link.
[in] | _name | Name of the parent link. |
void sdf::SDF_VERSION_NAMESPACE::Joint::SetPoseRelativeTo | ( | const std::string & | _frame | ) |
Set the name of the coordinate frame relative to which this object's pose is expressed.
An empty value indicates that the frame is relative to the child link frame.
[in] | _frame | The name of the pose relative-to frame. |
void sdf::SDF_VERSION_NAMESPACE::Joint::SetRawPose | ( | const gz::math::Pose3d & | _pose | ) |
Set the pose of the joint.
[in] | _pose | The pose of the joint. |
void sdf::SDF_VERSION_NAMESPACE::Joint::SetThreadPitch | ( | double | _threadPitch | ) |
Set the thread pitch (only valid for screw joints)
[in] | _threadPitch | The thread pitch of the joint |
void sdf::SDF_VERSION_NAMESPACE::Joint::SetType | ( | const JointType | _jointType | ) |
Set the joint type.
[in] | _jointType | The type of joint. |
double sdf::SDF_VERSION_NAMESPACE::Joint::ThreadPitch | ( | ) | const |
Get the thread pitch (only valid for screw joints)
sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Joint::ToElement | ( | ) | const |
JointType sdf::SDF_VERSION_NAMESPACE::Joint::Type | ( | ) | const |
Get the joint type.