Gazebo Sim

API Reference

7.7.0

This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a joint entity. More...

#include <gz/sim/Joint.hh>

Public Member Functions

 Joint (sim::Entity _entity=kNullEntity)
 Constructor. More...
 
std::optional< std::vector< sdf::JointAxis > > Axis (const EntityComponentManager &_ecm) const
 Get the joint axis. More...
 
std::optional< std::stringChildLinkName (const EntityComponentManager &_ecm) const
 Get the child link name. More...
 
void EnablePositionCheck (EntityComponentManager &_ecm, bool _enable=true) const
 By default, Gazebo will not report positions for a joint, so functions like Position will return nullopt. This function can be used to enable joint position check. More...
 
void EnableTransmittedWrenchCheck (EntityComponentManager &_ecm, bool _enable=true) const
 By default, Gazebo will not report transmitted wrench for a joint, so functions like TransmittedWrench will return nullopt. This function can be used to enable joint transmitted wrench check. More...
 
void EnableVelocityCheck (EntityComponentManager &_ecm, bool _enable=true) const
 By default, Gazebo will not report velocities for a joint, so functions like Velocity will return nullopt. This function can be used to enable joint velocity check. More...
 
sim::Entity Entity () const
 Get the entity which this Joint is related to. More...
 
std::optional< std::stringName (const EntityComponentManager &_ecm) const
 Get the joint's unscoped name. More...
 
std::optional< std::stringParentLinkName (const EntityComponentManager &_ecm) const
 Get the parent link name. More...
 
std::optional< ModelParentModel (const EntityComponentManager &_ecm) const
 Get the parent model. More...
 
std::optional< math::Pose3dPose (const EntityComponentManager &_ecm) const
 Get the pose of the joint. More...
 
std::optional< std::vector< double > > Position (const EntityComponentManager &_ecm) const
 Get the position of the joint. More...
 
void ResetEntity (sim::Entity _newEntity)
 Reset Entity to a new one. More...
 
void ResetPosition (EntityComponentManager &_ecm, const std::vector< double > &_positions)
 Reset the joint positions. More...
 
void ResetVelocity (EntityComponentManager &_ecm, const std::vector< double > &_velocities)
 Reset the joint velocities. More...
 
sim::Entity SensorByName (const EntityComponentManager &_ecm, const std::string &_name) const
 Get the ID of a sensor entity which is an immediate child of this joint. More...
 
uint64_t SensorCount (const EntityComponentManager &_ecm) const
 Get the number of sensors which are immediate children of this joint. More...
 
std::vector< sim::EntitySensors (const EntityComponentManager &_ecm) const
 Get all sensors which are immediate children of this joint. More...
 
void SetEffortLimits (EntityComponentManager &_ecm, const std::vector< math::Vector2d > &_limits)
 Set the effort limits on a joint axis. More...
 
void SetForce (EntityComponentManager &_ecm, const std::vector< double > &_forces)
 Set force on this joint. If both forces and velocities are set, only forces are applied. More...
 
void SetPositionLimits (EntityComponentManager &_ecm, const std::vector< math::Vector2d > &_limits)
 Set the position limits on a joint axis. More...
 
void SetVelocity (EntityComponentManager &_ecm, const std::vector< double > &_velocities)
 Set velocity on this joint. Only applied if no forces are set. More...
 
void SetVelocityLimits (EntityComponentManager &_ecm, const std::vector< math::Vector2d > &_limits)
 Set the velocity limits on a joint axis. More...
 
std::optional< double > ThreadPitch (const EntityComponentManager &_ecm) const
 Get the thread pitch of the joint. More...
 
std::optional< std::vector< msgs::Wrench > > TransmittedWrench (const EntityComponentManager &_ecm) const
 Get the position of the joint. More...
 
std::optional< sdf::JointType > Type (const EntityComponentManager &_ecm) const
 Get the joint type. More...
 
bool Valid (const EntityComponentManager &_ecm) const
 Check whether this joint correctly refers to an entity that has a components::Joint. More...
 
std::optional< std::vector< double > > Velocity (const EntityComponentManager &_ecm) const
 Get the velocity of the joint. More...
 

Detailed Description

This class provides wrappers around entities and components which are more convenient and straight-forward to use than dealing with the EntityComponentManager directly. All the functions provided here are meant to be used with a joint entity.

For example, given a joint's entity, find the value of its name component, one could use the entity-component manager (ecm) directly as follows:

std::string name = ecm.Component<components::Name>(entity)->Data();

Using this class however, the same information can be obtained with a simpler function call:

Joint joint(entity); std::string name = joint.Name(ecm);

Constructor & Destructor Documentation

◆ Joint()

Joint ( sim::Entity  _entity = kNullEntity)
explicit

Constructor.

Parameters
[in]_entityJoint entity

Member Function Documentation

◆ Axis()

std::optional<std::vector<sdf::JointAxis> > Axis ( const EntityComponentManager _ecm) const

Get the joint axis.

Parameters
[in]_ecmEntity-component manager.
Returns
Axis of the joint or nullopt if the entity does not have a components::JointAxis or components::JointAxis2 component.

◆ ChildLinkName()

std::optional<std::string> ChildLinkName ( const EntityComponentManager _ecm) const

Get the child link name.

Parameters
[in]_ecmEntity-component manager.
Returns
Child link name or nullopt if the entity does not have a components::ChildLinkName component.

◆ EnablePositionCheck()

void EnablePositionCheck ( EntityComponentManager _ecm,
bool  _enable = true 
) const

By default, Gazebo will not report positions for a joint, so functions like Position will return nullopt. This function can be used to enable joint position check.

Parameters
[in]_ecmMutable reference to the ECM.
[in]_enableTrue to enable checks, false to disable. Defaults to true.

◆ EnableTransmittedWrenchCheck()

void EnableTransmittedWrenchCheck ( EntityComponentManager _ecm,
bool  _enable = true 
) const

By default, Gazebo will not report transmitted wrench for a joint, so functions like TransmittedWrench will return nullopt. This function can be used to enable joint transmitted wrench check.

Parameters
[in]_ecmMutable reference to the ECM.
[in]_enableTrue to enable checks, false to disable. Defaults to true.

◆ EnableVelocityCheck()

void EnableVelocityCheck ( EntityComponentManager _ecm,
bool  _enable = true 
) const

By default, Gazebo will not report velocities for a joint, so functions like Velocity will return nullopt. This function can be used to enable joint velocity check.

Parameters
[in]_ecmMutable reference to the ECM.
[in]_enableTrue to enable checks, false to disable. Defaults to true.

◆ Entity()

sim::Entity Entity ( ) const

Get the entity which this Joint is related to.

Returns
Joint entity.

◆ Name()

std::optional<std::string> Name ( const EntityComponentManager _ecm) const

Get the joint's unscoped name.

Parameters
[in]_ecmEntity-component manager.
Returns
Joint's name or nullopt if the entity does not have a components::Name component

◆ ParentLinkName()

std::optional<std::string> ParentLinkName ( const EntityComponentManager _ecm) const

Get the parent link name.

Parameters
[in]_ecmEntity-component manager.
Returns
Parent link name or nullopt if the entity does not have a components::ParentLinkName component.

◆ ParentModel()

std::optional<Model> ParentModel ( const EntityComponentManager _ecm) const

Get the parent model.

Parameters
[in]_ecmEntity-component manager.
Returns
Parent Model or nullopt if the entity does not have a components::ParentEntity component.

◆ Pose()

std::optional<math::Pose3d> Pose ( const EntityComponentManager _ecm) const

Get the pose of the joint.

Parameters
[in]_ecmEntity-component manager.
Returns
Pose of the joint or nullopt if the entity does not have a components::Pose component.

◆ Position()

std::optional<std::vector<double> > Position ( const EntityComponentManager _ecm) const

Get the position of the joint.

Parameters
[in]_ecmEntity-component manager.
Returns
Position of the joint or nullopt if position check is not enabled.
See also
EnablePositionCheck

◆ ResetEntity()

void ResetEntity ( sim::Entity  _newEntity)

Reset Entity to a new one.

Parameters
[in]_newEntityNew joint entity.

◆ ResetPosition()

void ResetPosition ( EntityComponentManager _ecm,
const std::vector< double > &  _positions 
)

Reset the joint positions.

Parameters
[in]_ecmEntity Component manager.
[in]_positionsJoint positions to reset to. The vector of positions should have the same size as the degrees of freedom of the joint.

◆ ResetVelocity()

void ResetVelocity ( EntityComponentManager _ecm,
const std::vector< double > &  _velocities 
)

Reset the joint velocities.

Parameters
[in]_ecmEntity Component manager.
[in]_velocitiesJoint velocities to reset to. This is different from SetVelocity as this modifies the internal state of the joint. The vector of velocities should have the same size as the degrees of freedom of the joint.

◆ SensorByName()

sim::Entity SensorByName ( const EntityComponentManager _ecm,
const std::string _name 
) const

Get the ID of a sensor entity which is an immediate child of this joint.

Parameters
[in]_ecmEntity-component manager.
[in]_nameSensor name.
Returns
Sensor entity.

◆ SensorCount()

uint64_t SensorCount ( const EntityComponentManager _ecm) const

Get the number of sensors which are immediate children of this joint.

Parameters
[in]_ecmEntity-component manager.
Returns
Number of sensors in this joint.

◆ Sensors()

std::vector<sim::Entity> Sensors ( const EntityComponentManager _ecm) const

Get all sensors which are immediate children of this joint.

Parameters
[in]_ecmEntity-component manager.
Returns
All sensors in this joint.

◆ SetEffortLimits()

void SetEffortLimits ( EntityComponentManager _ecm,
const std::vector< math::Vector2d > &  _limits 
)

Set the effort limits on a joint axis.

Parameters
[in]_ecmEntity Component manager.
[in]_limitsJoint limits to set to. The X() component of the Vector2 specifies the minimum effort limit, the Y() component stands for maximum limit. The vector of limits should have the same size as the degrees of freedom of the joint.

◆ SetForce()

void SetForce ( EntityComponentManager _ecm,
const std::vector< double > &  _forces 
)

Set force on this joint. If both forces and velocities are set, only forces are applied.

Parameters
[in]_ecmEntity Component manager.
[in]_forcesJoint force or torque commands (target forces or toruqes). The vector of forces should have the same size as the degrees of freedom of the joint.

◆ SetPositionLimits()

void SetPositionLimits ( EntityComponentManager _ecm,
const std::vector< math::Vector2d > &  _limits 
)

Set the position limits on a joint axis.

Parameters
[in]_ecmEntity Component manager.
[in]_limitsJoint limits to set to. The X() component of the Vector2 specifies the minimum position limit, the Y() component stands for maximum limit. The vector of limits should have the same size as the degrees of freedom of the joint.

◆ SetVelocity()

void SetVelocity ( EntityComponentManager _ecm,
const std::vector< double > &  _velocities 
)

Set velocity on this joint. Only applied if no forces are set.

Parameters
[in]_ecmEntity Component manager.
[in]_velocitiesJoint velocities commands (target velocities). This is different from ResetVelocity in that this does not modify the internal state of the joint. Instead, the physics engine is expected to compute the necessary joint torque for the commanded velocity and apply it in the next simulation step. The vector of velocities should have the same size as the degrees of freedom of the joint.

◆ SetVelocityLimits()

void SetVelocityLimits ( EntityComponentManager _ecm,
const std::vector< math::Vector2d > &  _limits 
)

Set the velocity limits on a joint axis.

Parameters
[in]_ecmEntity Component manager.
[in]_limitsJoint limits to set to. The X() component of the Vector2 specifies the minimum velocity limit, the Y() component stands for maximum limit. The vector of limits should have the same size as the degrees of freedom of the joint.

◆ ThreadPitch()

std::optional<double> ThreadPitch ( const EntityComponentManager _ecm) const

Get the thread pitch of the joint.

Parameters
[in]_ecmEntity-component manager.
Returns
Thread pitch of the joint or nullopt if the entity does not have a components::ThreadPitch component.

◆ TransmittedWrench()

std::optional<std::vector<msgs::Wrench> > TransmittedWrench ( const EntityComponentManager _ecm) const

Get the position of the joint.

Parameters
[in]_ecmEntity-component manager.
Returns
Transmitted wrench of the joint or nullopt if transmitted wrench check is not enabled.
See also
EnableTransmittedWrenchCheck

◆ Type()

std::optional<sdf::JointType> Type ( const EntityComponentManager _ecm) const

Get the joint type.

Parameters
[in]_ecmEntity-component manager.
Returns
Type of the joint or nullopt if the entity does not have a components::JointType component.

◆ Valid()

bool Valid ( const EntityComponentManager _ecm) const

Check whether this joint correctly refers to an entity that has a components::Joint.

Parameters
[in]_ecmEntity-component manager.
Returns
True if it's a valid joint in the manager.

◆ Velocity()

std::optional<std::vector<double> > Velocity ( const EntityComponentManager _ecm) const

Get the velocity of the joint.

Parameters
[in]_ecmEntity-component manager.
Returns
Velocity of the joint or nullopt if velocity check is not enabled.
See also
EnableVelocityCheck

The documentation for this class was generated from the following file: