33#ifndef DART_COLLISION_DART_DARTCOLLIDE_HPP_
34#define DART_COLLISION_DART_DARTCOLLIDE_HPP_
45int collide(CollisionObject* o1, CollisionObject* o2, CollisionResult&
result);
50 const Eigen::Vector3d& size0,
51 const Eigen::Isometry3d& T0,
52 const Eigen::Vector3d& size1,
53 const Eigen::Isometry3d& T1,
59 const Eigen::Vector3d& size0,
60 const Eigen::Isometry3d& T0,
62 const Eigen::Isometry3d& T1,
69 const Eigen::Isometry3d& T0,
70 const Eigen::Vector3d& size1,
71 const Eigen::Isometry3d& T1,
78 const Eigen::Isometry3d& c0,
80 const Eigen::Isometry3d& c1,
86 const double& cyl_rad,
87 const double& half_height,
88 const Eigen::Isometry3d& T0,
89 const double& sphere_rad,
90 const Eigen::Isometry3d& T1,
96 const double& cyl_rad,
97 const double& half_height,
98 const Eigen::Isometry3d& T0,
99 const Eigen::Vector3d& plane_normal,
100 const Eigen::Isometry3d& T1,
CollisionResult * result
Collision result of DART.
Definition FCLCollisionDetector.cpp:160
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:60