Skip to content

Commit

Permalink
API documentation common Get* feature (#162)
Browse files Browse the repository at this point in the history
* GetEngineInfo docs

Signed-off-by: anindex <[email protected]>

* GetWorldFromEngine docs

Signed-off-by: anindex <[email protected]>

* GetModelFromWorld docs

Signed-off-by: anindex <[email protected]>

* GetLinkFromModel docs

Signed-off-by: anindex <[email protected]>

* GetJointFromModel docs

Signed-off-by: anindex <[email protected]>

* GetShapeFromLink docs

Signed-off-by: anindex <[email protected]>

* GetJoint* docs

Signed-off-by: anindex <[email protected]>

* GetShape* docs

Signed-off-by: anindex <[email protected]>

* GetShapeFriction docs

Signed-off-by: anindex <[email protected]>

* Get bounding box docs

Signed-off-by: anindex <[email protected]>

* Refine docs

Signed-off-by: anindex <[email protected]>

Co-authored-by: anindex <[email protected]>
Co-authored-by: Claire Wang <[email protected]>
  • Loading branch information
3 people committed Jan 7, 2021
1 parent 361dd29 commit 691510c
Show file tree
Hide file tree
Showing 4 changed files with 44 additions and 2 deletions.
13 changes: 11 additions & 2 deletions include/ignition/physics/GetBoundingBox.hh
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,11 @@ namespace ignition
GetShapeBoundingBox,
GetShapeFromLink,
LinkFrameSemantics>;

/////////////////////////////////////////////////
/// \brief This feature retrieves the axis aligned bounding box for the
/// shapes attached to this link in the requested frame. The default frame
/// is the world frame.
class IGNITION_PHYSICS_VISIBLE GetLinkBoundingBox
: public virtual
FeatureWithRequirements<GetLinkBoundingBoxRequiredFeatures>
Expand Down Expand Up @@ -62,6 +67,10 @@ namespace ignition
GetLinkBoundingBox,
GetLinkFromModel,
ModelFrameSemantics>;

/////////////////////////////////////////////////
/// \brief This feature retrieves the axis aligned bounding box for the
/// model in the requested frame. The default frame is the world frame.
class IGNITION_PHYSICS_VISIBLE GetModelBoundingBox
: public virtual
FeatureWithRequirements<GetModelBoundingBoxRequiredFeatures>
Expand All @@ -73,8 +82,8 @@ namespace ignition
public: using AlignedBoxType =
typename FromPolicy<PolicyT>::template Use<AlignedBox>;

/// \brief Get the axis aligned bounding box for the links attached
/// to this model in the requested frame.
/// \brief Get the axis aligned bounding box for the model
/// in the requested frame.
/// \param[in] _referenceFrame
/// The desired frame for the bounding box. By default, this will be
/// the world frame.
Expand Down
17 changes: 17 additions & 0 deletions include/ignition/physics/GetEntities.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@ namespace ignition
{
namespace physics
{
/////////////////////////////////////////////////
/// \brief This feature retrieves the physics engine name in use.
class IGNITION_PHYSICS_VISIBLE GetEngineInfo : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
Expand All @@ -51,6 +53,9 @@ namespace ignition
};
};

/////////////////////////////////////////////////
/// \brief This feature retrieves the world pointer using index or name
/// from the physics engine in use.
class IGNITION_PHYSICS_VISIBLE GetWorldFromEngine : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
Expand Down Expand Up @@ -128,6 +133,9 @@ namespace ignition
};
};

/////////////////////////////////////////////////
/// \brief This feature retrieves the model pointer from the simulation
/// world by specifying world index and model index/name.
class IGNITION_PHYSICS_VISIBLE GetModelFromWorld : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
Expand Down Expand Up @@ -205,6 +213,9 @@ namespace ignition
};
};

/////////////////////////////////////////////////
/// \brief This feature retrieves the link pointer from the model
/// by specifying model index and link index/name.
class IGNITION_PHYSICS_VISIBLE GetLinkFromModel : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
Expand Down Expand Up @@ -282,6 +293,9 @@ namespace ignition
};
};

/////////////////////////////////////////////////
/// \brief This feature retrieves the joint pointer from the model
/// by specifying model index and joint index/name.
class IGNITION_PHYSICS_VISIBLE GetJointFromModel : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
Expand Down Expand Up @@ -359,6 +373,9 @@ namespace ignition
};
};

/////////////////////////////////////////////////
/// \brief This feature retrieves the shape pointer from the link
/// by specifying link index and shape index/name.
class IGNITION_PHYSICS_VISIBLE GetShapeFromLink : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
Expand Down
8 changes: 8 additions & 0 deletions include/ignition/physics/Joint.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,10 @@ namespace ignition
namespace physics
{
/////////////////////////////////////////////////
/// \brief This feature retrieves the generalized joint states such as
/// position, velocity, acceleration of the joint, applied force to the
/// joint and the transformation matrix from the joint's parent link to this
/// joint's child link based on its current position.
class IGNITION_PHYSICS_VISIBLE GetBasicJointState : public virtual Feature
{
/// \brief The Joint API for getting basic joint state
Expand Down Expand Up @@ -181,6 +185,10 @@ namespace ignition
};

/////////////////////////////////////////////////
/// \brief This feature retrieves the generalized joint properties such as
/// Degrees Of Freedom (DoF), the transformation matrix from the joint's
/// parent link to this joint and the transformation matrix from this joint
/// to its child link.
class IGNITION_PHYSICS_VISIBLE GetBasicJointProperties
: public virtual Feature
{
Expand Down
8 changes: 8 additions & 0 deletions include/ignition/physics/Shape.hh
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@ namespace ignition
namespace physics
{
/////////////////////////////////////////////////
/// \brief This feature retrieves the shape kinematic properties such as the
/// the relative transform from the the link frame to this shape frame.
class IGNITION_PHYSICS_VISIBLE GetShapeKinematicProperties
: public virtual Feature
{
Expand Down Expand Up @@ -87,6 +89,8 @@ namespace ignition
};

/////////////////////////////////////////////////
/// \brief This feature retrieves the shape collision properties such as
/// the shape surface friction coefficient and restitution coefficient.
class IGNITION_PHYSICS_VISIBLE GetShapeCollisionProperties
: public virtual Feature
{
Expand Down Expand Up @@ -129,6 +133,8 @@ namespace ignition
};

/////////////////////////////////////////////////
/// \brief This feature retrieves the shape's axis aligned bounding box in
/// the requested frame. The default frame is the world frame.
class IGNITION_PHYSICS_VISIBLE GetShapeBoundingBox
: public virtual FeatureWithRequirements<ShapeFrameSemantics>
{
Expand Down Expand Up @@ -251,6 +257,8 @@ namespace ignition
};

/////////////////////////////////////////////////
/// \brief This feature retrieves the shape's slip compliance of the first
/// and second friction direction in the friction pyramid model.
class IGNITION_PHYSICS_VISIBLE GetShapeFrictionPyramidSlipCompliance
: public virtual Feature
{
Expand Down

0 comments on commit 691510c

Please sign in to comment.