33 #ifndef DART_COLLISION_DART_DARTCOLLIDE_HPP_
34 #define DART_COLLISION_DART_DARTCOLLIDE_HPP_
37 #include <Eigen/Dense>
48 const Eigen::Vector3d& size0,
49 const Eigen::Isometry3d& T0,
50 const Eigen::Vector3d& size1,
51 const Eigen::Isometry3d& T1,
57 const Eigen::Vector3d& size0,
58 const Eigen::Isometry3d& T0,
60 const Eigen::Isometry3d& T1,
67 const Eigen::Isometry3d& T0,
68 const Eigen::Vector3d& size1,
69 const Eigen::Isometry3d& T1,
76 const Eigen::Isometry3d& c0,
78 const Eigen::Isometry3d& c1,
84 const double& cyl_rad,
85 const double& half_height,
86 const Eigen::Isometry3d& T0,
87 const double& sphere_rad,
88 const Eigen::Isometry3d& T1,
94 const double& cyl_rad,
95 const double& half_height,
96 const Eigen::Isometry3d& T0,
97 const Eigen::Vector3d& plane_normal,
98 const Eigen::Isometry3d& T1,
CollisionResult * result
Collision result of DART.
Definition: FCLCollisionDetector.cpp:160
::fcl::CollisionObject CollisionObject
Definition: BackwardCompatibility.hpp:161
::fcl::CollisionResult CollisionResult
Definition: BackwardCompatibility.hpp:166
int collideSphereSphere(CollisionObject *o1, CollisionObject *o2, const double &_r0, const Eigen::Isometry3d &c0, const double &_r1, const Eigen::Isometry3d &c1, CollisionResult &result)
Definition: DARTCollide.cpp:1316
int collideBoxSphere(CollisionObject *o1, CollisionObject *o2, const Eigen::Vector3d &size0, const Eigen::Isometry3d &T0, const double &r1, const Eigen::Isometry3d &T1, CollisionResult &result)
Definition: DARTCollide.cpp:1034
int collideSphereBox(CollisionObject *o1, CollisionObject *o2, const double &r0, const Eigen::Isometry3d &T0, const Eigen::Vector3d &size1, const Eigen::Isometry3d &T1, CollisionResult &result)
Definition: DARTCollide.cpp:1177
int collideBoxBox(CollisionObject *o1, CollisionObject *o2, const Eigen::Vector3d &size0, const Eigen::Isometry3d &T0, const Eigen::Vector3d &size1, const Eigen::Isometry3d &T1, CollisionResult &result)
Definition: DARTCollide.cpp:1005
int collide(CollisionObject *o1, CollisionObject *o2, CollisionResult &result)
Definition: DARTCollide.cpp:1533
int collideCylinderSphere(CollisionObject *o1, CollisionObject *o2, const double &cyl_rad, const double &half_height, const Eigen::Isometry3d &T0, const double &sphere_rad, const Eigen::Isometry3d &T1, CollisionResult &result)
Definition: DARTCollide.cpp:1371
int collideCylinderPlane(CollisionObject *o1, CollisionObject *o2, const double &cyl_rad, const double &half_height, const Eigen::Isometry3d &T0, const Eigen::Vector3d &plane_normal, const Eigen::Isometry3d &T1, CollisionResult &result)
Definition: DARTCollide.cpp:1452
Definition: BulletCollisionDetector.cpp:65