Go to the documentation of this file.
   18 #ifndef GZ_PHYSICS_GEOMETRY_HH_ 
   19 #define GZ_PHYSICS_GEOMETRY_HH_ 
   21 #include <Eigen/Geometry> 
   23 #define DETAIL_IGN_PHYSICS_MAKE_BOTH_PRECISIONS(Type, Dim) \ 
   24   using Type ## Dim ## d = Type<double, Dim>; \ 
   25   using Type ## Dim ## f = Type<float, Dim>; 
   32 #define IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS(Type) \ 
   33   DETAIL_IGN_PHYSICS_MAKE_BOTH_PRECISIONS(Type, 2) \ 
   34   DETAIL_IGN_PHYSICS_MAKE_BOTH_PRECISIONS(Type, 3) 
   43     template <
typename Scalar, std::
size_t Dim>
 
   44     using Pose = Eigen::Transform<Scalar, Dim, Eigen::Isometry>;
 
   47     template <
typename Scalar, std::
size_t Dim>
 
   48     using Vector = Eigen::Matrix<Scalar, Dim, 1>;
 
   51     template <
typename Scalar, std::
size_t Dim>
 
   55     template <
typename Scalar, std::
size_t Dim>
 
   59     template <
typename Scalar, std::
size_t Dim>
 
   67     template <
typename Scalar, std::
size_t Dim>
 
   72     template <
typename PolicyT>
 
   79       using Scalar = 
typename PolicyT::Scalar;
 
   80       enum { 
Dim = PolicyT::Dim };
 
   82       template<
template <
typename, std::
size_t> 
class Type>
 
   83       using Use = Type<Scalar, Dim>;
 
   86     template<
typename Scalar>
 
   91       return Eigen::Rotation2D<Scalar>(_angle*_axis[0]);
 
   94     template <
typename Scalar>
 
   99       return Eigen::AngleAxis<Scalar>(_angle, _axis);
 
  
This struct is used to conveniently convert from a policy to a geometric type. Example usage:
Definition: gz/physics/Geometry.hh:77
Eigen::AlignedBox< Scalar, Dim > AlignedBox
Definition: gz/physics/Geometry.hh:68
typename PolicyT::Scalar Scalar
Definition: gz/physics/Geometry.hh:79
Eigen::Matrix< Scalar, Dim, 1 > Vector
Definition: gz/physics/Geometry.hh:48
@ Dim
Definition: gz/physics/Geometry.hh:80
Type< Scalar, Dim > Use
Definition: gz/physics/Geometry.hh:83
AngularVector< Scalar, Dim > torque
Definition: gz/physics/Geometry.hh:62
Vector< Scalar, Dim > LinearVector
Definition: gz/physics/Geometry.hh:52
Eigen::Transform< Scalar, Dim, Eigen::Isometry > Pose
This is used by ignition-physics to represent rigid body transforms in 2D or 3D simulations....
Definition: gz/physics/Geometry.hh:44
Eigen::Rotation2D< Scalar > Rotate(const Scalar &_angle, const AngularVector< Scalar, 2 > &_axis)
Definition: gz/physics/Geometry.hh:87
LinearVector< Scalar, Dim > force
Definition: gz/physics/Geometry.hh:63
IGN_PHYSICS_MAKE_ALL_TYPE_COMBOS(FrameData) template< typename Scalar
Definition: gz/physics/Geometry.hh:60
Vector< Scalar,(Dim *(Dim-1))/2 > AngularVector
Definition: gz/physics/Geometry.hh:56