Skip to content

Commit

Permalink
Tutorials and API doc back port (#187)
Browse files Browse the repository at this point in the history
Backport tutorials and API to citadel

Co-authored-by: Le Thai An <[email protected]>
Co-authored-by: anindex <[email protected]>
Co-authored-by: Louise Poubel <[email protected]>
  • Loading branch information
4 people authored Jan 22, 2021
1 parent b1876f0 commit a862a66
Show file tree
Hide file tree
Showing 18 changed files with 1,110 additions and 24 deletions.
4 changes: 4 additions & 0 deletions include/ignition/physics/BoxShape.hh
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,10 @@ namespace ignition
};
};

/////////////////////////////////////////////////
/// \brief This feature constructs a new box shape and attaches the
/// desired pose in the link frame. The pose could be defined to be the box
/// center point or any corner in actual implementation.
class IGNITION_PHYSICS_VISIBLE AttachBoxShapeFeature
: public virtual FeatureWithRequirements<BoxShapeCast>
{
Expand Down
15 changes: 15 additions & 0 deletions include/ignition/physics/ConstructEmpty.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,13 +26,18 @@ namespace ignition {
namespace physics {

/////////////////////////////////////////////////
/// \brief This feature constructs an empty world and return its pointer
/// from the current physics engine in use.
class ConstructEmptyWorldFeature : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
class Engine : public virtual Feature::Engine<PolicyT, FeaturesT>
{
public: using WorldPtrType = WorldPtr<PolicyT, FeaturesT>;

/// \brief Construct an empty world and attach a given name to it.
/// \return
/// The WorldPtrType of the constructed world.
public: WorldPtrType ConstructEmptyWorld(const std::string &_name);
};

Expand All @@ -45,13 +50,18 @@ class ConstructEmptyWorldFeature : public virtual Feature
};

/////////////////////////////////////////////////
/// \brief This feature constructs an empty model and return its pointer
/// from the given world.
class ConstructEmptyModelFeature : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
class World : public virtual Feature::World<PolicyT, FeaturesT>
{
public: using ModelPtrType = ModelPtr<PolicyT, FeaturesT>;

/// \brief Construct an empty model and attach a given name to it.
/// \return
/// The ModelPtrType of the constructed model.
public: ModelPtrType ConstructEmptyModel(const std::string &_name);
};

Expand All @@ -64,13 +74,18 @@ class ConstructEmptyModelFeature : public virtual Feature
};

/////////////////////////////////////////////////
/// \brief This feature constructs an empty link and return its pointer
/// from the given model.
class ConstructEmptyLinkFeature : public virtual Feature
{
public: template <typename PolicyT, typename FeaturesT>
class Model : public virtual Feature::Model<PolicyT, FeaturesT>
{
public: using LinkPtrType = LinkPtr<PolicyT, FeaturesT>;

/// \brief Construct an empty link and attach a given name to it.
/// \return
/// The LinkPtrType of the constructed link.
public: LinkPtrType ConstructEmptyLink(const std::string &_name);
};

Expand Down
15 changes: 15 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 Expand Up @@ -92,6 +95,10 @@ namespace ignition
};
};

/////////////////////////////////////////////////
/// \brief This feature constructs a new cylinder shape and attaches the
/// desired pose in the link frame. The pose could be defined to be the
/// cylinder center point in actual implementation.
class IGNITION_PHYSICS_VISIBLE AttachCylinderShapeFeature
: public virtual FeatureWithRequirements<CylinderShapeCast>
{
Expand All @@ -105,6 +112,14 @@ namespace ignition

public: using ShapePtrType = CylinderShapePtr<PolicyT, FeaturesT>;

/// \brief Rigidly attach a CylinderShape to this link.
/// \param[in] _radius
/// The radius of the cylinder.
/// \param[in] _height
/// The height of the cylinder.
/// \param[in] _pose
/// The desired pose of the CylinderShape relative to the Link frame.
/// \returns a ShapePtrType to the newly constructed CylinderShape
public: ShapePtrType AttachCylinderShape(
const std::string &_name = "cylinder",
Scalar _radius = 1.0,
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
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
13 changes: 13 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 @@ -103,6 +107,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 @@ -178,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 Expand Up @@ -316,6 +327,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
7 changes: 5 additions & 2 deletions include/ignition/physics/PlaneShape.hh
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,9 @@ namespace physics
};

/////////////////////////////////////////////////
/// \brief \brief This feature constructs a new plane shape and attaches the
/// desired point, which the plane passes thorugh in the link frame. The
/// default point is at zero coordinate.
class AttachPlaneShapeFeature
: public virtual FeatureWithRequirements<PlaneShapeCast>
{
Expand All @@ -132,8 +135,8 @@ namespace physics
/// Name to give to the PlaneShape
/// \param[in] _normal
/// Normal vector for the plane
/// \param[in] _offset
/// Offset of the plane
/// \param[in] _point
/// The point that the plane passes through (the origin by default)
/// \returns the PlaneShapePtr that was just created.
public: PlaneShapePtr<PolicyT, FeaturesT> AttachPlaneShape(
const std::string &_name,
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
12 changes: 12 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 @@ -167,6 +173,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 @@ -249,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 Expand Up @@ -284,6 +294,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
Loading

0 comments on commit a862a66

Please sign in to comment.