Gazebo Gazebo

API Reference

6.16.0
gz/sim/Joint.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2023 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 GZ_GAZEBO_JOINT_HH_
18 #define GZ_GAZEBO_JOINT_HH_
19 
20 #include <memory>
21 #include <optional>
22 #include <string>
23 #include <vector>
24 
25 #include <gz/msgs/wrench.pb.h>
26 #include <gz/utils/ImplPtr.hh>
27 
28 #include <gz/math/Pose3.hh>
29 #include <gz/math/Vector2.hh>
30 #include <gz/math/Vector3.hh>
31 
32 #include <sdf/Joint.hh>
33 #include <sdf/JointAxis.hh>
34 
35 #include "gz/sim/config.hh"
37 #include "gz/sim/Export.hh"
38 #include "gz/sim/Model.hh"
39 #include "gz/sim/Types.hh"
40 
41 namespace ignition
42 {
43  namespace gazebo
44  {
45  // Inline bracket to help doxygen filtering.
46  inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
47  //
67  class IGNITION_GAZEBO_VISIBLE Joint
68  {
71  public: explicit Joint(gazebo::Entity _entity = kNullEntity);
72 
75  public: gazebo::Entity Entity() const;
76 
79  public: void ResetEntity(gazebo::Entity _newEntity);
80 
85  public: bool Valid(const EntityComponentManager &_ecm) const;
86 
91  public: std::optional<std::string> Name(
92  const EntityComponentManager &_ecm) const;
93 
98  public: std::optional<std::string> ParentLinkName(
99  const EntityComponentManager &_ecm) const;
100 
105  public: std::optional<std::string> ChildLinkName(
106  const EntityComponentManager &_ecm) const;
107 
112  public: std::optional<math::Pose3d> Pose(
113  const EntityComponentManager &_ecm) const;
114 
119  public: std::optional<double> ThreadPitch(
120  const EntityComponentManager &_ecm) const;
121 
126  public: std::optional<std::vector<sdf::JointAxis>> Axis(
127  const EntityComponentManager &_ecm) const;
128 
133  public: std::optional<sdf::JointType> Type(
134  const EntityComponentManager &_ecm) const;
135 
141  public: gazebo::Entity SensorByName(const EntityComponentManager &_ecm,
142  const std::string &_name) const;
143 
147  public: std::vector<gazebo::Entity> Sensors(
148  const EntityComponentManager &_ecm) const;
149 
154  public: uint64_t SensorCount(const EntityComponentManager &_ecm) const;
155 
164  public: void SetVelocity(EntityComponentManager &_ecm,
165  const std::vector<double> &_velocities);
166 
173  public: void SetForce(EntityComponentManager &_ecm,
174  const std::vector<double> &_forces);
175 
182  public: void SetVelocityLimits(EntityComponentManager &_ecm,
183  const std::vector<math::Vector2d> &_limits);
184 
191  public: void SetEffortLimits(EntityComponentManager &_ecm,
192  const std::vector<math::Vector2d> &_limits);
193 
200  public: void SetPositionLimits(EntityComponentManager &_ecm,
201  const std::vector<math::Vector2d> &_limits);
202 
208  public: void ResetPosition(EntityComponentManager &_ecm,
209  const std::vector<double> &_positions);
210 
217  public: void ResetVelocity(EntityComponentManager &_ecm,
218  const std::vector<double> &_velocities);
219 
226  public: void EnableVelocityCheck(EntityComponentManager &_ecm,
227  bool _enable = true) const;
228 
235  public: void EnablePositionCheck(EntityComponentManager &_ecm,
236  bool _enable = true) const;
237 
244  public: void EnableTransmittedWrenchCheck(EntityComponentManager &_ecm,
245  bool _enable = true) const;
246 
252  public: std::optional<std::vector<double>> Velocity(
253  const EntityComponentManager &_ecm) const;
254 
260  public: std::optional<std::vector<double>> Position(
261  const EntityComponentManager &_ecm) const;
262 
268  public: std::optional<std::vector<msgs::Wrench>> TransmittedWrench(
269  const EntityComponentManager &_ecm) const;
270 
275  public: std::optional<Model> ParentModel(
276  const EntityComponentManager &_ecm) const;
277 
279  IGN_UTILS_IMPL_PTR(dataPtr)
280  };
281  }
282  }
283 }
284 #endif
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
Joint(gazebo::Entity _entity=kNullEntity)
Constructor.
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.