Ignition Physics

API Reference

2.3.0
ignition::physics Namespace Reference

Namespaces

 mesh
 
 sdf
 

Classes

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  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  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...
 
class  CollisionFilterMaskFeature
 
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 return its pointer from the given model. More...
 
class  ConstructEmptyModelFeature
 This feature constructs an empty model and return its pointer from the given world. More...
 
class  ConstructEmptyWorldFeature
 This feature constructs an empty world and return 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 ignition-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  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  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...
 
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...
 
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  SetCylinderShapeProperties
 This feature sets the CylinderShape properties such as the cylinder radius and height. 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  SetJointTransformFromParentFeature
 
class  SetJointTransformToChildFeature
 
class  SetJointVelocityCommandFeature
 This feature sets the commanded value of generalized velocity of this Joint. 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  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
 
struct  WorldPose
 
struct  WorldPoses
 
struct  WriteOptions
 A struct that defines options for writing data to a CompositeData object. More...
 

Typedefs

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 >
 
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 ignition-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 RemoveEntities = FeatureList< RemoveModelFromWorld >
 
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
 

Functions

template<typename Specification >
constexpr std::size_t CountUpperLimitOfExpectedData ()
 This provides an upper limit on the number of expected data types in a CompositeData specification. This is an upper limit because when a data type is specified multiple times within a specficiation, it will be counted multiple times. As long as each data type is only specified once, it will provide an exact count. More...
 
template<typename Specification >
constexpr std::size_t CountUpperLimitOfRequiredData ()
 Same as CountUpperLimitOfExpectedData() except it will count required data instead. More...
 
template<typename Specification , template< typename > class SpecFinder>
constexpr std::size_t CountUpperLimitOfSpecifiedData ()
 Same as CountUpperLimitOfExpectedData() except you can specify what kind of data to count using SpecFinder. SpecFinder must accept a data specification (or void) as a template argument and provide a type called Data. See FindExpected and FindRequired below for examples. More...
 
 IGN_PHYSICS_DECLARE_JOINT_TYPE (FixedJoint) class AttachFixedJointFeature
 
 IGN_PHYSICS_DECLARE_SHAPE_TYPE (PlaneShape) class GetPlaneShapeProperties
 
 IGN_PHYSICS_DECLARE_SHAPE_TYPE (SphereShape) class GetSphereShapeProperties
 
 IGN_PHYSICS_DECLARE_SHAPE_TYPE (CylinderShape) class GetCylinderShapeProperties
 
 IGN_PHYSICS_DECLARE_SHAPE_TYPE (BoxShape) class GetBoxShapeProperties
 
 IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS (FrameData) template< typename Scalar
 
 IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS (RelativePose) template< typename Scalar
 
 IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS (RelativeRotationMatrix) template< typename Scalar > using RelativeQuaternion
 
 IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS (RelativeTorque) template< typename Scalar
 
std::size_t Dim std::ostreamoperator<< (std::ostream &stream, const FrameData< Scalar, Dim > &_frame)
 
template<typename Q , std::size_t Dim, typename CoordinateSpace >
std::ostreamoperator<< (std::ostream &stream, const RelativeQuantity< Q, Dim, CoordinateSpace > &_fq)
 
template<typename Scalar >
Eigen::Rotation2D< Scalar > Rotate (const Scalar &_angle, const AngularVector< Scalar, 2 > &_axis)
 
template<typename Scalar >
Eigen::AngleAxis< Scalar > Rotate (const Scalar &_angle, const AngularVector< Scalar, 3 > &_axis)
 

Variables

const std::size_t INVALID_ENTITY_ID
 This constant-value should be used to indicate that an Entity ID is invalid (i.e. does not refer to a real entity). More...
 

Typedef Documentation

◆ AlignedBox

using AlignedBox = Eigen::AlignedBox<Scalar, Dim>

◆ AlignedBox2d

using AlignedBox2d = AlignedBox <double, 2 >

◆ AlignedBox2f

using AlignedBox2f = AlignedBox <float, 2 >

◆ AlignedBox3d

using AlignedBox3d = AlignedBox <double, 3 >

◆ AlignedBox3f

using AlignedBox3f = AlignedBox <float, 3 >

◆ AngularVector

using AngularVector = Vector<Scalar, (Dim*(Dim-1))/2>

◆ AngularVector2d

using AngularVector2d = AngularVector <double, 2 >

◆ AngularVector2f

using AngularVector2f = AngularVector <float, 2 >

◆ AngularVector3d

using AngularVector3d = AngularVector <double, 3 >

◆ AngularVector3f

using AngularVector3f = AngularVector <float, 3 >

◆ FeaturePolicy2d

using FeaturePolicy2d = FeaturePolicy<double, 2>

◆ FeaturePolicy2f

using FeaturePolicy2f = FeaturePolicy<float, 2>

◆ FeaturePolicy3d

using FeaturePolicy3d = FeaturePolicy<double, 3>

◆ FeaturePolicy3f

using FeaturePolicy3f = FeaturePolicy<float, 3>

◆ FindFeatures2d

◆ FindFeatures2f

◆ FindFeatures3d

◆ FindFeatures3f

◆ GetLinkBoundingBoxRequiredFeatures

◆ GetModelBoundingBoxRequiredFeatures

◆ Implements

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.

Below are simpler templates that hardcode the dimensionality and precision.

◆ Implements2d

using Implements2d = Implements<FeaturePolicy2d, FeatureListT>

◆ Implements2f

using Implements2f = Implements<FeaturePolicy2f, FeatureListT>

◆ Implements3d

using Implements3d = Implements<FeaturePolicy3d, FeatureListT>

◆ Implements3f

using Implements3f = Implements<FeaturePolicy3f, FeatureListT>

◆ LinearVector

using LinearVector = Vector<Scalar, Dim>

◆ LinearVector2d

using LinearVector2d = LinearVector <double, 2 >

◆ LinearVector2f

using LinearVector2f = LinearVector <float, 2 >

◆ LinearVector3d

using LinearVector3d = LinearVector <double, 3 >

◆ LinearVector3f

using LinearVector3f = LinearVector <float, 3 >

◆ Pose

using Pose = Eigen::Transform<Scalar, Dim, Eigen::Isometry>

This is used by ignition-physics to represent rigid body transforms in 2D or 3D simulations. The precision can be chosen as float or scalar.

◆ Pose2d

using Pose2d = Pose <double, 2 >

◆ Pose2f

using Pose2f = Pose <float, 2 >

◆ Pose3d

using Pose3d = Pose <double, 3 >

◆ Pose3f

using Pose3f = Pose <float, 3 >

◆ RelativeAlignedBox

using RelativeAlignedBox = RelativeQuantity< AlignedBox<Scalar, Dim>, Dim, detail::AABBSpace<Scalar, Dim> >

◆ RelativeForce

using RelativeForce = RelativeQuantity< LinearVector<Scalar, Dim>, Dim, detail::VectorSpace<Scalar, Dim> >

◆ RelativeFrameData

using RelativeFrameData = RelativeQuantity< FrameData<Scalar, Dim>, Dim, detail::FrameSpace<Scalar, Dim> >

◆ RelativePose

using RelativePose = RelativeQuantity< Pose<Scalar, Dim>, Dim, detail::SESpace<Scalar, Dim> >

◆ RelativePosition

using RelativePosition = RelativeQuantity< LinearVector<Scalar, Dim>, Dim, detail::EuclideanSpace<Scalar, Dim> >

◆ RelativeQuaterniond

using RelativeQuaterniond = RelativeQuaternion<double>

◆ RelativeQuaternionf

using RelativeQuaternionf = RelativeQuaternion<float>

◆ RelativeRotationMatrix

using RelativeRotationMatrix = RelativeQuantity< Eigen::Matrix<Scalar, Dim, Dim>, Dim, detail::SOSpace<Scalar, Dim, Eigen::Matrix<Scalar, Dim, Dim> >>

◆ RelativeTorque

using RelativeTorque = RelativeQuantity< AngularVector<Scalar, Dim>, Dim, detail::VectorSpace<Scalar, (Dim*(Dim-1))/2> >

◆ RemoveEntities

◆ RequestEngine2d

◆ RequestEngine2f

◆ RequestEngine3d

◆ RequestEngine3f

◆ Vector

using Vector = Eigen::Matrix<Scalar, Dim, 1>

◆ Vector2d

using Vector2d = Vector <double, 2 >

◆ Vector2f

using Vector2f = Vector <float, 2 >

◆ Vector3d

using Vector3d = Vector <double, 3 >

◆ Vector3f

using Vector3f = Vector <float, 3 >

◆ void_t

using void_t = void

TODO(MXG): Remove this and use std::void_t instead when migrating to C++17

Function Documentation

◆ CountUpperLimitOfExpectedData()

constexpr std::size_t ignition::physics::CountUpperLimitOfExpectedData ( )

This provides an upper limit on the number of expected data types in a CompositeData specification. This is an upper limit because when a data type is specified multiple times within a specficiation, it will be counted multiple times. As long as each data type is only specified once, it will provide an exact count.

This is a constexpr so it will be evaluated at compile-time and behaves like a constant literal.

◆ CountUpperLimitOfRequiredData()

constexpr std::size_t ignition::physics::CountUpperLimitOfRequiredData ( )

Same as CountUpperLimitOfExpectedData() except it will count required data instead.

◆ CountUpperLimitOfSpecifiedData()

constexpr std::size_t ignition::physics::CountUpperLimitOfSpecifiedData ( )

Same as CountUpperLimitOfExpectedData() except you can specify what kind of data to count using SpecFinder. SpecFinder must accept a data specification (or void) as a template argument and provide a type called Data. See FindExpected and FindRequired below for examples.

◆ IGN_PHYSICS_DECLARE_JOINT_TYPE()

ignition::physics::IGN_PHYSICS_DECLARE_JOINT_TYPE ( FixedJoint  )

Attach this link to another link using a FixedJoint.

Parameters
[in]_parentThe parent link for the joint. Pass in a nullptr to attach the link to the world.
[in]_nameThe name for this joint.
Returns
A reference to the newly constructed FixedJoint. You can use the SetJointTransformFromParentFeature and SetJointTransformToChildFeature on this JointPtr to set the relative transform between the parent and child if your physics engine offers those features.

◆ IGN_PHYSICS_DECLARE_SHAPE_TYPE() [1/4]

ignition::physics::IGN_PHYSICS_DECLARE_SHAPE_TYPE ( PlaneShape  )

Get the normal vector for this plane.

Returns
the normal vector for this plane.

Get a point on the plane.

Returns
the offset of the plane.

◆ IGN_PHYSICS_DECLARE_SHAPE_TYPE() [2/4]

ignition::physics::IGN_PHYSICS_DECLARE_SHAPE_TYPE ( SphereShape  )

Get the radius of this SphereShape

Returns
the radius of this SphereShape

◆ IGN_PHYSICS_DECLARE_SHAPE_TYPE() [3/4]

ignition::physics::IGN_PHYSICS_DECLARE_SHAPE_TYPE ( CylinderShape  )

Get the radius of this CylinderShape

Returns
the radius of this CylinderShape

Get the height (length along the local z-axis) of this CylinderShape.

Returns
the height of this CylinderShape

◆ IGN_PHYSICS_DECLARE_SHAPE_TYPE() [4/4]

ignition::physics::IGN_PHYSICS_DECLARE_SHAPE_TYPE ( BoxShape  )

Get the dimensions of this BoxShape

Returns
the dimensions of this BoxShape

◆ IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS() [1/4]

ignition::physics::IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS ( FrameData  )

◆ IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS() [2/4]

IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS ( RelativePose  )

◆ IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS() [3/4]

ignition::physics::IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS ( RelativeRotationMatrix  )

◆ IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS() [4/4]

ignition::physics::IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS ( RelativeTorque  )

◆ operator<<() [1/2]

◆ operator<<() [2/2]

std::ostream& ignition::physics::operator<< ( std::ostream stream,
const RelativeQuantity< Q, Dim, CoordinateSpace > &  _fq 
)

◆ Rotate() [1/2]

Eigen::Rotation2D<Scalar> ignition::physics::Rotate ( const Scalar &  _angle,
const AngularVector< Scalar, 2 > &  _axis 
)

◆ Rotate() [2/2]

Eigen::AngleAxis<Scalar> ignition::physics::Rotate ( const Scalar &  _angle,
const AngularVector< Scalar, 3 > &  _axis 
)

Variable Documentation

◆ INVALID_ENTITY_ID

const std::size_t INVALID_ENTITY_ID
Initial value:

This constant-value should be used to indicate that an Entity ID is invalid (i.e. does not refer to a real entity).