gz/sim/Joint.hh
uint64_t Entity
An Entity identifies a single object in simulation such as a model, link, or light....
Definition: gz/sim/Entity.hh:58
This library is part of the Gazebo project.
STL class.
The EntityComponentManager constructs, deletes, and returns components and entities....
Definition: gz/sim/EntityComponentManager.hh:66
STL class.
std::optional< std::vector< msgs::Wrench > > TransmittedWrench(const EntityComponentManager &_ecm) const
Get the transmitted wrench of the joint.
gazebo::Entity Entity() const
Get the entity which this Joint is related to.
std::optional< math::Pose3d > Pose(const EntityComponentManager &_ecm) const
Get the pose of the joint.
gazebo::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.
std::optional< std::vector< double > > Position(const EntityComponentManager &_ecm) const
Get the position of the joint.
Component< NoData, class JointTag > Joint
A component that identifies an entity as being a joint.
Definition: gz/sim/components/Joint.hh:33
void SetPositionLimits(EntityComponentManager &_ecm, const std::vector< math::Vector2d > &_limits)
Set the position limits on a joint axis.
std::vector< gazebo::Entity > Sensors(const EntityComponentManager &_ecm) const
Get all sensors which are immediate children of this joint.
void EnableVelocityCheck(EntityComponentManager &_ecm, bool _enable=true) const
By default, Gazebo will not report velocities for a joint, so functions like Velocity will return nul...
Component< gz::math::Pose3d, class PoseTag > Pose
A component type that contains pose, gz::math::Pose3d, information.
Definition: gz/sim/components/Pose.hh:35
std::optional< std::string > Name(const EntityComponentManager &_ecm) const
Get the joint's unscoped name.
std::optional< std::vector< double > > Velocity(const EntityComponentManager &_ecm) const
Get the velocity of the joint.
const Entity kNullEntity
Indicates a non-existant or invalid Entity.
Definition: gz/sim/Entity.hh:61
void SetVelocity(EntityComponentManager &_ecm, const std::vector< double > &_velocities)
Set velocity on this joint. Only applied if no forces are set.
void ResetPosition(EntityComponentManager &_ecm, const std::vector< double > &_positions)
Reset the joint positions.
Component< double, class ThreadPitchTag > ThreadPitch
A component used to store the thread pitch of a screw joint.
Definition: gz/sim/components/ThreadPitch.hh:33
void ResetEntity(gazebo::Entity _newEntity)
Reset Entity to a new one.
std::optional< std::string > ChildLinkName(const EntityComponentManager &_ecm) const
Get the child link name.
std::optional< std::string > ParentLinkName(const EntityComponentManager &_ecm) const
Get the parent link name.
std::optional< std::vector< sdf::JointAxis > > Axis(const EntityComponentManager &_ecm) const
Get the joint axis.
Component< std::string, class ChildLinkNameTag, serializers::StringSerializer > ChildLinkName
A component used to indicate that a model is childlinkname (i.e. not moveable).
Definition: gz/sim/components/ChildLinkName.hh:37
void SetVelocityLimits(EntityComponentManager &_ecm, const std::vector< math::Vector2d > &_limits)
Set the velocity limits on a joint axis.
void SetEffortLimits(EntityComponentManager &_ecm, const std::vector< math::Vector2d > &_limits)
Set the effort limits on a joint axis.
Component< std::string, class ParentLinkNameTag, serializers::StringSerializer > ParentLinkName
Holds the name of the entity's parent link.
Definition: gz/sim/components/ParentLinkName.hh:36
This class provides wrappers around entities and components which are more convenient and straight-fo...
Definition: gz/sim/Joint.hh:67
void EnablePositionCheck(EntityComponentManager &_ecm, bool _enable=true) const
By default, Gazebo will not report positions for a joint, so functions like Position will return null...
void ResetVelocity(EntityComponentManager &_ecm, const std::vector< double > &_velocities)
Reset the joint velocities.
uint64_t SensorCount(const EntityComponentManager &_ecm) const
Get the number of sensors which are immediate children of this joint.
std::optional< double > ThreadPitch(const EntityComponentManager &_ecm) const
Get the thread pitch of the joint.
bool Valid(const EntityComponentManager &_ecm) const
Check whether this joint correctly refers to an entity that has a components::Joint.
void EnableTransmittedWrenchCheck(EntityComponentManager &_ecm, bool _enable=true) const
By default, Gazebo will not report transmitted wrench for a joint, so functions like TransmittedWrenc...
std::optional< sdf::JointType > Type(const EntityComponentManager &_ecm) const
Get the joint type.
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.
Component< std::string, class NameTag, serializers::StringSerializer > Name
This component holds an entity's name. The component has no concept of scoped names nor does it care ...
Definition: gz/sim/components/Name.hh:37
std::optional< Model > ParentModel(const EntityComponentManager &_ecm) const
Get the parent model.