From 691510ce263e6c2fb2b2b7f07c37bdfc46b79279 Mon Sep 17 00:00:00 2001 From: Le Thai An Date: Thu, 3 Dec 2020 23:51:39 +0100 Subject: [PATCH] API documentation common Get* feature (#162) * GetEngineInfo docs Signed-off-by: anindex * GetWorldFromEngine docs Signed-off-by: anindex * GetModelFromWorld docs Signed-off-by: anindex * GetLinkFromModel docs Signed-off-by: anindex * GetJointFromModel docs Signed-off-by: anindex * GetShapeFromLink docs Signed-off-by: anindex * GetJoint* docs Signed-off-by: anindex * GetShape* docs Signed-off-by: anindex * GetShapeFriction docs Signed-off-by: anindex * Get bounding box docs Signed-off-by: anindex * Refine docs Signed-off-by: anindex Co-authored-by: anindex Co-authored-by: Claire Wang <22240514+claireyywang@users.noreply.github.com> --- include/ignition/physics/GetBoundingBox.hh | 13 +++++++++++-- include/ignition/physics/GetEntities.hh | 17 +++++++++++++++++ include/ignition/physics/Joint.hh | 8 ++++++++ include/ignition/physics/Shape.hh | 8 ++++++++ 4 files changed, 44 insertions(+), 2 deletions(-) diff --git a/include/ignition/physics/GetBoundingBox.hh b/include/ignition/physics/GetBoundingBox.hh index 95e63a6ce..7767dd040 100644 --- a/include/ignition/physics/GetBoundingBox.hh +++ b/include/ignition/physics/GetBoundingBox.hh @@ -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 @@ -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 @@ -73,8 +82,8 @@ namespace ignition public: using AlignedBoxType = typename FromPolicy::template Use; - /// \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. diff --git a/include/ignition/physics/GetEntities.hh b/include/ignition/physics/GetEntities.hh index b399f5466..98c04beda 100644 --- a/include/ignition/physics/GetEntities.hh +++ b/include/ignition/physics/GetEntities.hh @@ -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 @@ -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 @@ -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 @@ -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 @@ -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 @@ -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 diff --git a/include/ignition/physics/Joint.hh b/include/ignition/physics/Joint.hh index b9127e099..24af4ebe6 100644 --- a/include/ignition/physics/Joint.hh +++ b/include/ignition/physics/Joint.hh @@ -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 @@ -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 { diff --git a/include/ignition/physics/Shape.hh b/include/ignition/physics/Shape.hh index 1573dd8ee..91980390c 100644 --- a/include/ignition/physics/Shape.hh +++ b/include/ignition/physics/Shape.hh @@ -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 { @@ -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 { @@ -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 { @@ -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 {