Skip to content

Commit

Permalink
API documentation common Set* features (#165)
Browse files Browse the repository at this point in the history
* RemoveModelFromWorld doc
* SetBasicJointState doc
* SetJointVelocity doc
* SetShape* doc
* SetCylinderShapeProperties* doc
* SetFreeGroupWorldPose and Velocity doc
* Refine docs

Co-authored-by: anindex <[email protected]>
  • Loading branch information
2 people authored and claireyywang committed Jan 7, 2021
1 parent f546657 commit bd24418
Show file tree
Hide file tree
Showing 5 changed files with 36 additions and 4 deletions.
3 changes: 3 additions & 0 deletions include/ignition/physics/CylinderShape.hh
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,9 @@ namespace ignition
};
};

/////////////////////////////////////////////////
/// \brief This feature sets the CylinderShape properties such as
/// the cylinder radius and height.
class IGNITION_PHYSICS_VISIBLE SetCylinderShapeProperties
: public virtual FeatureWithRequirements<CylinderShapeCast>
{
Expand Down
25 changes: 21 additions & 4 deletions include/ignition/physics/FreeGroup.hh
Original file line number Diff line number Diff line change
Expand Up @@ -110,21 +110,29 @@ namespace ignition
};

/////////////////////////////////////////////////
/// While a physics engine with maximal coordinates can provide
/// \brief This features sets the FreeGroup pose in world frame. However,
/// while a physics engine with maximal coordinates can provide
/// Link::SetWorldPose and similar functions for setting velocity
/// regardless of the kinematic constraints on that link, this behavior
/// is not well defined and difficult to implement with generalized
/// coordinates. The FreeGroup::SetWorldPose function provides an
/// analog to both `Link::SetWorldPose` and `Model::SetWorldPose`.
/// for FreeGroup is not well defined and difficult to implement
/// with generalized coordinates. The FreeGroup::SetWorldPose function
/// should provide an analog to both Link::SetWorldPose and
/// Model::SetWorldPose.
class IGNITION_PHYSICS_VISIBLE SetFreeGroupWorldPose
: public virtual FeatureWithRequirements<FindFreeGroupFeature>
{
/// \brief This class defines the FreeGroup concept, which represents a
/// group of links that are not connected to the world with any kinematic
/// constraints. This class also provides a rough definition of this
/// FreeGroup pose in world frame. See FindFreeGroupFeature class
/// documentation for more detail.
public: template <typename PolicyT, typename FeaturesT>
class FreeGroup : public virtual Entity<PolicyT, FeaturesT>
{
public: using PoseType =
typename FromPolicy<PolicyT>::template Use<Pose>;

/// \brief Set this FreeGroup pose in world frame.
public: void SetWorldPose(const PoseType &_pose);
};

Expand All @@ -141,9 +149,16 @@ namespace ignition
};

/////////////////////////////////////////////////
/// \brief This features sets the FreeGroup linear and angular velocity in
/// world frame.
class IGNITION_PHYSICS_VISIBLE SetFreeGroupWorldVelocity
: public virtual FeatureWithRequirements<FindFreeGroupFeature>
{
/// \brief This class defines the FreeGroup concept, which represents a
/// group of links that are not connected to the world with any kinematic
/// constraints. This class also provides a rough definition of this
/// FreeGroup linear and angular velocity in world frame. See
/// FindFreeGroupFeature class documentation for more detail.
public: template <typename PolicyT, typename FeaturesT>
class FreeGroup : public virtual Entity<PolicyT, FeaturesT>
{
Expand All @@ -153,9 +168,11 @@ namespace ignition
public: using AngularVelocity =
typename FromPolicy<PolicyT>::template Use<AngularVector>;

/// \brief Set this FreeGroup linear velocity in world frame.
public: void SetWorldLinearVelocity(
const LinearVelocity &_linearVelocity);

/// \brief Set this FreeGroup angular velocity in world frame.
public: void SetWorldAngularVelocity(
const AngularVelocity &_angularVelocity);
};
Expand Down
5 changes: 5 additions & 0 deletions include/ignition/physics/Joint.hh
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,9 @@ namespace ignition
};

/////////////////////////////////////////////////
/// \brief This feature sets the generalized joint states such as
/// position, velocity, acceleration of the joint and the applied force to
/// the joint.
class IGNITION_PHYSICS_VISIBLE SetBasicJointState : public virtual Feature
{
/// \brief The Joint API for setting basic joint state
Expand Down Expand Up @@ -316,6 +319,8 @@ namespace ignition
};

/////////////////////////////////////////////////
/// \brief This feature sets the commanded value of generalized velocity of
/// this Joint.
class IGNITION_PHYSICS_VISIBLE SetJointVelocityCommandFeature
: public virtual Feature
{
Expand Down
3 changes: 3 additions & 0 deletions include/ignition/physics/RemoveEntities.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,9 @@ namespace ignition
{
namespace physics
{
/////////////////////////////////////////////////
/// \brief This feature removes a Model entity from the index-specified
/// World.
class IGNITION_PHYSICS_VISIBLE RemoveModelFromWorld : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
Expand Down
4 changes: 4 additions & 0 deletions include/ignition/physics/Shape.hh
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,8 @@ namespace ignition
};

/////////////////////////////////////////////////
/// \brief This feature sets the Shape collision properties such as
/// the Shape surface friction coefficient and restitution coefficient.
class IGNITION_PHYSICS_VISIBLE SetShapeCollisionProperties
: public virtual Feature
{
Expand Down Expand Up @@ -284,6 +286,8 @@ namespace ignition
};

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

0 comments on commit bd24418

Please sign in to comment.