17 #ifndef GAZEBO_PHYSICS_BULLET_BULLETTYPES_HH_
18 #define GAZEBO_PHYSICS_BULLET_BULLETTYPES_HH_
20 #include <boost/shared_ptr.hpp>
21 #include <ignition/math/Vector4.hh>
34 class BulletCollision;
36 class BulletMotionState;
61 return ignition::math::Vector3d(
62 _bt.getX(), _bt.getY(), _bt.getZ());
69 const ignition::math::Vector3d &_vec)
71 return btVector3(_vec.X(), _vec.Y(), _vec.Z());
80 return ignition::math::Vector4d(_bt.getX(), _bt.getY(),
81 _bt.getZ(), _bt.getW());
88 const ignition::math::Vector4d &_vec)
90 return btVector4(_vec.X(), _vec.Y(), _vec.Z(), _vec.W());
97 const btTransform &_bt)
99 ignition::math::Pose3d pose;
100 pose.Pos() = ConvertVector3Ign(_bt.getOrigin());
101 pose.Rot().W() = _bt.getRotation().getW();
102 pose.Rot().X() = _bt.getRotation().getX();
103 pose.Rot().Y() = _bt.getRotation().getY();
104 pose.Rot().Z() = _bt.getRotation().getZ();
112 const ignition::math::Pose3d &_pose)
116 trans.setOrigin(ConvertVector3(_pose.Pos()));
117 trans.setRotation(btQuaternion(_pose.Rot().X(), _pose.Rot().Y(),
118 _pose.Rot().Z(), _pose.Rot().W()));
boost::shared_ptr< BulletSurfaceParams > BulletSurfaceParamsPtr
Definition: BulletTypes.hh:46
static btTransform ConvertPose(const ignition::math::Pose3d &_pose)
Convert an ignition math pose to a bullet transform.
Definition: BulletTypes.hh:111
boost::shared_ptr< BulletMotionState > BulletMotionStatePtr
Definition: BulletTypes.hh:43
static btVector4 ConvertVector4dIgn(const ignition::math::Vector4d &_vec)
Convert an ignition math Vector4d to a bullet btVector4.
Definition: BulletTypes.hh:87
Bullet surface parameters.
Definition: BulletSurfaceParams.hh:35
boost::shared_ptr< BulletCollision > BulletCollisionPtr
Definition: BulletTypes.hh:39
static ignition::math::Pose3d ConvertPoseIgn(const btTransform &_bt)
Convert a bullet transform to an ignition math pose.
Definition: BulletTypes.hh:96
boost::shared_ptr< BulletPhysics > BulletPhysicsPtr
Definition: BulletTypes.hh:44
static ignition::math::Vector3d ConvertVector3Ign(const btVector3 &_bt)
Convert a bullet btVector3 to an ignition Vector3d.
Definition: BulletTypes.hh:58
static ignition::math::Vector4d ConvertVector4dIgn(const btVector4 &_bt)
Convert a bullet btVector4 to an ignition math Vector4d.
Definition: BulletTypes.hh:77
boost::shared_ptr< BulletLink > BulletLinkPtr
Definition: BulletTypes.hh:42
A set of functions for converting between the math types used by gazebo and bullet.
Definition: BulletTypes.hh:54
static btVector3 ConvertVector3(const ignition::math::Vector3d &_vec)
Convert an ignition Vector3d to a bullet btVector3.
Definition: BulletTypes.hh:68
boost::shared_ptr< BulletRayShape > BulletRayShapePtr
Definition: BulletTypes.hh:45