|
class | AddedMass |
|
class | AddLinkExternalForceTorque |
|
struct | ApplyExternalForceTorques |
|
struct | ApplyGeneralizedForces |
|
class | AttachBoxShapeFeature |
| 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. More...
|
|
class | AttachCapsuleShapeFeature |
| This feature constructs a new capsule shape and attaches the desired pose in the link frame. The pose could be defined to be the capsule center point in actual implementation. More...
|
|
class | AttachConeShapeFeature |
| This feature constructs a new cone shape and attaches the desired pose in the link frame. The pose could be defined to be the cone center point in actual implementation. More...
|
|
class | AttachCylinderShapeFeature |
| 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. More...
|
|
class | AttachEllipsoidShapeFeature |
| This feature constructs a new ellipsoid shape and attaches the desired pose in the link frame. The pose could be defined to be the ellipsoid center point in actual implementation. More...
|
|
class | AttachPlaneShapeFeature |
| 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. More...
|
|
class | AttachPrismaticJointFeature |
| Provide the API for attaching a Link to another Link (or directly to the World) with a prismatic joint. After calling AttachPrismaticJoint the Link's parent joint will be a prismatic joint. More...
|
|
class | AttachRevoluteJointFeature |
| Provide the API for attaching a Link to another Link (or directly to the World) with a revolute joint. After calling AttachRevoluteJoint, the Link's parent joint will be a revolute joint. More...
|
|
class | AttachSphereShapeFeature |
| This feature constructs a new sphere shape and attaches the desired pose in the link frame. The pose is defined as the sphere center point in actual implementation. More...
|
|
class | CanReadExpectedData |
|
class | CanReadRequiredData |
| CanReadRequiredData provides compile-time static analysis to ensure that the inheriting class provides a Read(~) function overload for each of the data types that are listed as required in the Specification. It also provides a function that will invoke Read(~) on each of the required data types (you may indicate whether or not it should only invoke them on unqueried data). More...
|
|
class | CanWriteExpectedData |
|
class | CanWriteRequiredData |
| CanWriteRequiredData provides compile-time static analysis to ensure that the inheriting class provides a Write(~) function overload for each of the data types that are listed as required in the Specification. It also provides a function that will invoke Write(~) on each of the required data types (you may indicate whether or not it should only invoke them on unqueried data). More...
|
|
struct | ChangedWorldPoses |
| ChangedWorldPoses has the same definition as WorldPoses. This type provides a way to keep track of which poses have changed in a simulation step. More...
|
|
class | CollisionDetector |
|
class | CollisionFilterMaskFeature |
|
class | CollisionPairMaxContacts |
|
class | CompleteFrameSemantics |
| This feature will apply frame semantics to all objects. More...
|
|
class | CompositeData |
| The CompositeData class allows arbitrary data structures to be composed together, copied, and moved with type erasure. More...
|
|
struct | ConstCompatible |
| Contains a static constexpr field named value which will be true if the type From has a const-quality less than or equal to the type To . More...
|
|
struct | ConstCompatible< To, const From > |
|
class | ConstructEmptyLinkFeature |
| This feature constructs an empty link and returns its pointer from the given model. More...
|
|
class | ConstructEmptyModelFeature |
| [ConstructEmptyWorld] More...
|
|
class | ConstructEmptyNestedModelFeature |
| This feature constructs an empty nested model and returns its pointer from the given world. More...
|
|
class | ConstructEmptyWorldFeature |
| This feature constructs an empty world and returns its pointer from the current physics engine in use. More...
|
|
struct | Contacts |
|
struct | DataStatusMask |
| This struct encodes criteria for CompositeData::DataStatus so that Read and Write operations can be done for specific types of data (ie. required and unqueried or only existing data). It is used by OperateOnSpecifiedData at run-time. More...
|
|
class | DetachJointFeature |
|
struct | Empty |
| Useful as a blank placeholder in template metaprogramming. More...
|
|
class | Entity |
| This is the base class of all "proxy objects". The "proxy
objects" are essentially interfaces into the actual objects which exist inside of the various physics engine implementations. The proxy objects contain the minimal amount of data (e.g. a unique identifier, a reference-counter for the implementation object, and a reference to the implementation interface that it needs) necessary to interface with the object inside of the implementation that it refers to. More...
|
|
class | EntityPtr |
|
class | ExpectData< Expected > |
| ExpectData is an extension of CompositeData which indicates that the composite expects to be operating on the data types listed in its template arguments. All of the expected types will benefit from very high-speed operations when being accessed from an object of type ExpectData<Expected>. The ordinary CompositeData class needs to perform a map lookup on the data type whenever one of its functions is called, but an ExpectData<T> object does not need to perform any map lookup when performing an operation on T (e.g. .Get<T>(), .Insert<T>(), .Query<T>(), .Has<T>(), etc). More...
|
|
class | Feature |
| This class defines the concept of a Feature. It should be inherited by classes that define some plugin feature. More...
|
|
struct | FeatureList |
| Use a FeatureList to aggregate a list of Features. More...
|
|
struct | FeaturePolicy |
| FeaturePolicy is a "policy class" used to provide metadata to features about what kind of simulation engine they are going to be used in. More...
|
|
struct | FeatureWithConflicts |
| If your feature is known to conflict with any other feature, then you should have your feature class inherit FeatureWithConflicts<...>, and pass it a list of the features that it conflicts with. More...
|
|
struct | FeatureWithRequirements |
| If your feature is known to require any other features, then you should have your feature class inherit FeatureWithRequirements<...>, and pass it a list of the features that it requires. More...
|
|
struct | FindExpected |
| This allows us to specify that we are interested in expected data while performing template metaprogramming. More...
|
|
struct | FindFeatures |
|
struct | FindRequired |
| This allows us to specify that we are interested in required data while performing template metaprogramming. More...
|
|
struct | ForceTorque |
|
class | ForwardStep |
| ForwardStep is a feature that allows a simulation of a world to take one step forward in time. More...
|
|
struct | FrameData |
| The FrameData struct fully describes the kinematic state of a Frame with "Dim" dimensions and "Scalar" precision. Dim is allowed to be 2 or 3, and Scalar is allowed to be double or float. We provide the following fully qualified types: More...
|
|
class | FrameID |
| Container for specifying Frame IDs. We do not want to use a generic integer type for this, because it may lead to bugs where a plain integer is mistaken for a FrameID. This also allows the compiler to always perform argument deduction successfully. More...
|
|
class | FrameSemantics |
| FrameSemantics is an Interface that can be provided by gz-physics engines to provide users with easy ways to express kinematic quantities in terms of frames and compute their values in terms of arbitrary frames of reference. More...
|
|
class | FreeGroupFrameSemantics |
| This feature provides an interface between the Model and Link classes and the FreeGroup class, which represents a group of links that are not connected to the world with any kinematic constraints. A FreeGroup can represent a single connected group of links that forms a tree with the root of the tree connected to the world with a FreeJoint, but it can also represent a group of other FreeGroups. Each FreeGroup has 1 canonical link, whose frame is used for getting and setting properties like pose and velocity. If the FreeGroup is a single tree of connected links, the canonical link should be the root of that tree. If the FreeGroup contains multiple FreeGroups, the canonical link should be selected from one of the component FreeGroups. More...
|
|
struct | FreeVector |
|
struct | FromPolicy |
| This struct is used to conveniently convert from a policy to a geometric type. Example usage: More...
|
|
struct | GeneralizedParameters |
|
class | GetBasicJointProperties |
| 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. More...
|
|
class | GetBasicJointState |
| 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. More...
|
|
class | GetContactsFromLastStepFeature |
| GetContactsFromLastStepFeature is a feature for retrieving the list of contacts generated in the previous simulation step. More...
|
|
class | GetEngineInfo |
| This feature retrieves the physics engine name in use. More...
|
|
struct | GetEntities |
|
class | GetJointFromModel |
| This feature retrieves the joint pointer from the model by specifying model index and joint index/name. More...
|
|
class | GetJointTransmittedWrench |
|
class | GetLinkBoundingBox |
| 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. More...
|
|
class | GetLinkFromModel |
| This feature retrieves the link pointer from the model by specifying model index and link index/name. More...
|
|
class | GetModelBoundingBox |
| This feature retrieves the axis aligned bounding box for the model in the requested frame. The default frame is the world frame. More...
|
|
class | GetModelFromWorld |
| This feature retrieves the model pointer from the simulation world by specifying world index and model index/name. More...
|
|
class | GetNestedModelFromModel |
| This feature retrieves the nested model pointer from the parent model by specifying the name or index of the nested model. More...
|
|
class | GetRayIntersectionFromLastStepFeature |
| GetRayIntersectionFromLastStepFeature is a feature for retrieving the ray intersection generated in the previous simulation step. More...
|
|
class | GetShapeBoundingBox |
| This feature retrieves the shape's axis aligned bounding box in the requested frame. The default frame is the world frame. More...
|
|
class | GetShapeCollisionProperties |
| This feature retrieves the shape collision properties such as the shape surface friction coefficient and restitution coefficient. More...
|
|
class | GetShapeFrictionPyramidSlipCompliance |
| This feature retrieves the shape's slip compliance of the first and second friction direction in the friction pyramid model. More...
|
|
class | GetShapeFromLink |
| This feature retrieves the shape pointer from the link by specifying link index and shape index/name. More...
|
|
class | GetShapeKinematicProperties |
| This feature retrieves the shape kinematic properties such as the the relative transform from the the link frame to this shape frame. More...
|
|
class | GetWorldFromEngine |
| This feature retrieves the world pointer using index or name from the physics engine in use. More...
|
|
class | Gravity |
| Get and set the World's gravity vector in a specified frame. More...
|
|
struct | IsExpectedBy |
| Provides a constexpr field named value whose value is true if and only if Data is expected by Specification. More...
|
|
struct | IsRequiredBy |
| Provides a constexpr field named value whose value is true if and only if Data is required by Specification. More...
|
|
class | JointFrameSemantics |
| This feature will apply frame semantics to Joint objects. More...
|
|
struct | JointPositions |
|
class | LinkFrameSemantics |
| This feature will apply frame semantics to Link objects. More...
|
|
class | ModelFrameSemantics |
| This feature will apply frame semantics to Model objects. More...
|
|
class | OperateOnSpecifiedData |
| OperateOnSpecifiedData allows us to statically analyze whether a class (Performer) can perform an operation on all the relevant types within a CompositeData Specification. It also provides functions for performing that operation. More...
|
|
struct | PIDValues |
|
struct | Point |
|
struct | ReadOptions |
| ReadOptions provides customization for the ReadRequiredData and ReadExpectedData functions provided by CanReadRequiredData and CanReadExpectedData. More...
|
|
class | RelativeQuantity |
| The RelativeQuantity class is a wrapper for classes that represent mathematical quantities (e.g. points, vectors, matrices, transforms). The purpose of this wrapper is to endow raw mathematical quantities with frame semantics, so that they can express the frame of reference of their values. More...
|
|
class | RemoveModelFromWorld |
| This feature removes a Model entity from the index-specified World. More...
|
|
class | RemoveNestedModelFromModel |
| This feature removes a nested Model entity from the specified parent Model. More...
|
|
struct | RequestEngine |
| This class provides utilities for inspecting what features are available in a plugin. More...
|
|
struct | RequestFeatures |
| This class can be used to request features from an entity, or identify what features are missing from an entity. More...
|
|
class | RequireData< Required > |
| RequireData is an extension of ExpectData which indicates that the composite requires the existence of any data types that are listed in its template arguments. More...
|
|
struct | ServoControlCommands |
|
class | SetBasicJointState |
| This feature sets the generalized joint states such as position, velocity, acceleration of the joint and the applied force to the joint. More...
|
|
class | SetBoxShapeProperties |
|
class | SetCapsuleShapeProperties |
| This feature sets the CapsuleShape properties such as the capsule radius and length. More...
|
|
class | SetConeShapeProperties |
| This feature sets the ConeShape properties such as the cone radius and height. More...
|
|
class | SetContactPropertiesCallbackFeature |
| SetContactPropertiesCallbackFeature is a feature for setting the properties of a contact after it is created but before it affects the forward step. More...
|
|
class | SetCylinderShapeProperties |
| This feature sets the CylinderShape properties such as the cylinder radius and height. More...
|
|
class | SetEllipsoidShapeProperties |
| This feature sets the EllipsoidShape properties such as the ellipsoid radii. More...
|
|
class | SetFreeGroupWorldPose |
| 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 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. More...
|
|
class | SetFreeGroupWorldVelocity |
| This features sets the FreeGroup linear and angular velocity in world frame. More...
|
|
class | SetJointEffortLimitsFeature |
| This feature sets the min and max value of effort of this Joint. More...
|
|
class | SetJointPositionLimitsFeature |
| This feature sets the min and max generalized position of this Joint. More...
|
|
class | SetJointTransformFromParentFeature |
|
class | SetJointTransformToChildFeature |
|
class | SetJointVelocityCommandFeature |
| This feature sets the commanded value of generalized velocity of this Joint. More...
|
|
class | SetJointVelocityLimitsFeature |
| This feature sets the min and max value of generalized velocity of this Joint. More...
|
|
class | SetMimicConstraintFeature |
| This feature applies a Mimic constraint to an axis of this Joint. This constraint encodes a linear relationship between the output position of two joint axes. One joint axis is labelled as the leader and the other as the follower. The multiplier, offset, and reference parameters determine the linear relationship according to the following equation: More...
|
|
class | SetPlaneShapeProperties |
|
class | SetPrismaticJointProperties |
| Provide the API for setting a prismatic joint's axis. Not all physics engines are able to change properties during run-time, so some might support getting the joint axis but not setting it. More...
|
|
class | SetRevoluteJointProperties |
| Provide the API for setting a revolute joint's axis. Not all physics engines are able to change properties during run-time, so some might support getting the joint axis but not setting it. More...
|
|
class | SetShapeCollisionProperties |
| This feature sets the Shape collision properties such as the Shape surface friction coefficient and restitution coefficient. More...
|
|
class | SetShapeFrictionPyramidSlipCompliance |
| This feature sets the Shape's slip compliance of the first and second friction direction in the friction pyramid model. More...
|
|
class | SetShapeKinematicProperties |
|
class | SetSphereShapeProperties |
|
class | ShapeFrameSemantics |
|
class | Solver |
|
class | SpecifyData |
| The SpecifyData class allows you to form combinations of data specifications. In other words, you can freely mix invocations to RequireData and ExpectData. Example usage: More...
|
|
struct | TimeStep |
|
struct | type |
| This can be used to turn a type into a function argument, which is useful for template metaprogramming. More...
|
|
struct | VelocityControlCommands |
|
class | WorldModelFeature |
| This feature retrieves a model proxy of a world so that model APIs can be used on the world, e.g., to access a world joint. More...
|
|
struct | WorldPose |
|
struct | WorldPoses |
|
struct | Wrench |
|
struct | WriteOptions |
| A struct that defines options for writing data to a CompositeData object. More...
|
|
|
template<typename Scalar , std::size_t Dim> |
using | AlignedBox = Eigen::AlignedBox< Scalar, Dim > |
|
using | AlignedBox2d = AlignedBox< double, 2 > |
|
using | AlignedBox2f = AlignedBox< float, 2 > |
|
using | AlignedBox3d = AlignedBox< double, 3 > |
|
using | AlignedBox3f = AlignedBox< float, 3 > |
|
template<typename Scalar , std::size_t Dim> |
using | AngularVector = Vector< Scalar,(Dim *(Dim-1))/2 > |
|
using | AngularVector2d = AngularVector< double, 2 > |
|
using | AngularVector2f = AngularVector< float, 2 > |
|
using | AngularVector3d = AngularVector< double, 3 > |
|
using | AngularVector3f = AngularVector< float, 3 > |
|
using | FeaturePolicy2d = FeaturePolicy< double, 2 > |
|
using | FeaturePolicy2f = FeaturePolicy< float, 2 > |
|
using | FeaturePolicy3d = FeaturePolicy< double, 3 > |
|
using | FeaturePolicy3f = FeaturePolicy< float, 3 > |
|
template<typename FeatureListT > |
using | FindFeatures2d = FindFeatures< FeaturePolicy2d, FeatureListT > |
|
template<typename FeatureListT > |
using | FindFeatures2f = FindFeatures< FeaturePolicy2f, FeatureListT > |
|
template<typename FeatureListT > |
using | FindFeatures3d = FindFeatures< FeaturePolicy3d, FeatureListT > |
|
template<typename FeatureListT > |
using | FindFeatures3f = FindFeatures< FeaturePolicy3f, FeatureListT > |
|
using | GetLinkBoundingBoxRequiredFeatures = FeatureList< GetShapeBoundingBox, GetShapeFromLink, LinkFrameSemantics > |
|
using | GetModelBoundingBoxRequiredFeatures = FeatureList< GetLinkBoundingBox, GetLinkFromModel, ModelFrameSemantics > |
|
using | GravityRequiredFeatures = FeatureList< FrameSemantics > |
|
template<typename PolicyT , typename FeatureListT > |
using | Implements = detail::ExtractImplementation< PolicyT, FeatureListT > |
| Physics plugins should inherit this class and pass it a FeatureList containing all the features that their plugin intends to implement. More...
|
|
template<typename FeatureListT > |
using | Implements2d = Implements< FeaturePolicy2d, FeatureListT > |
|
template<typename FeatureListT > |
using | Implements2f = Implements< FeaturePolicy2f, FeatureListT > |
|
template<typename FeatureListT > |
using | Implements3d = Implements< FeaturePolicy3d, FeatureListT > |
|
template<typename FeatureListT > |
using | Implements3f = Implements< FeaturePolicy3f, FeatureListT > |
|
template<typename Scalar , std::size_t Dim> |
using | LinearVector = Vector< Scalar, Dim > |
|
using | LinearVector2d = LinearVector< double, 2 > |
|
using | LinearVector2f = LinearVector< float, 2 > |
|
using | LinearVector3d = LinearVector< double, 3 > |
|
using | LinearVector3f = LinearVector< float, 3 > |
|
template<typename Scalar , std::size_t Dim> |
using | Pose = Eigen::Transform< Scalar, Dim, Eigen::Isometry > |
| This is used by gz-physics to represent rigid body transforms in 2D or 3D simulations. The precision can be chosen as float or scalar. More...
|
|
using | Pose2d = Pose< double, 2 > |
|
using | Pose2f = Pose< float, 2 > |
|
using | Pose3d = Pose< double, 3 > |
|
using | Pose3f = Pose< float, 3 > |
|
using | RelativeAlignedBox = RelativeQuantity< AlignedBox< Scalar, Dim >, Dim, detail::AABBSpace< Scalar, Dim > > |
|
using | RelativeForce = RelativeQuantity< LinearVector< Scalar, Dim >, Dim, detail::VectorSpace< Scalar, Dim > > |
|
using | RelativeFrameData = RelativeQuantity< FrameData< Scalar, Dim >, Dim, detail::FrameSpace< Scalar, Dim > > |
|
template<typename Scalar , std::size_t Dim> |
using | RelativePose = RelativeQuantity< Pose< Scalar, Dim >, Dim, detail::SESpace< Scalar, Dim > > |
|
template<typename Scalar , std::size_t Dim> |
using | RelativePosition = RelativeQuantity< LinearVector< Scalar, Dim >, Dim, detail::EuclideanSpace< Scalar, Dim > > |
|
using | RelativeQuaterniond = RelativeQuaternion< double > |
|
using | RelativeQuaternionf = RelativeQuaternion< float > |
|
using | RelativeRotationMatrix = RelativeQuantity< Eigen::Matrix< Scalar, Dim, Dim >, Dim, detail::SOSpace< Scalar, Dim, Eigen::Matrix< Scalar, Dim, Dim > >> |
|
using | RelativeTorque = RelativeQuantity< AngularVector< Scalar, Dim >, Dim, detail::VectorSpace< Scalar,(Dim *(Dim-1))/2 > > |
|
using | RelativeWrench = RelativeQuantity< Wrench< Scalar, Dim >, Dim, detail::WrenchSpace< Scalar, Dim > > |
|
using | RemoveEntities = FeatureList< RemoveModelFromWorld, RemoveNestedModelFromModel > |
|
template<typename FeatureList > |
using | RequestEngine2d = RequestEngine< FeaturePolicy2d, FeatureList > |
|
template<typename FeatureList > |
using | RequestEngine2f = RequestEngine< FeaturePolicy2f, FeatureList > |
|
template<typename FeatureList > |
using | RequestEngine3d = RequestEngine< FeaturePolicy3d, FeatureList > |
|
template<typename FeatureList > |
using | RequestEngine3f = RequestEngine< FeaturePolicy3f, FeatureList > |
|
template<typename Scalar , std::size_t Dim> |
using | Vector = Eigen::Matrix< Scalar, Dim, 1 > |
|
using | Vector2d = Vector< double, 2 > |
|
using | Vector2f = Vector< float, 2 > |
|
using | Vector3d = Vector< double, 3 > |
|
using | Vector3f = Vector< float, 3 > |
|
template<typename... > |
using | void_t = void |
|
using | Wrench2d = Wrench< double, 2 > |
|
using | Wrench2f = Wrench< float, 2 > |
|
using | Wrench3d = Wrench< double, 3 > |
|
using | Wrench3f = Wrench< float, 3 > |
|