33#ifndef DART_COLLISION_DART_DARTCOLLIDE_HPP_
34#define DART_COLLISION_DART_DARTCOLLIDE_HPP_
43int collide(CollisionObject* o1, CollisionObject* o2,
47 const Eigen::Vector3d& size0,
const Eigen::Isometry3d& T0,
48 const Eigen::Vector3d& size1,
const Eigen::Isometry3d& T1,
52 const Eigen::Vector3d& size0,
const Eigen::Isometry3d& T0,
53 const double& r1,
const Eigen::Isometry3d& T1,
57 const double& r0,
const Eigen::Isometry3d& T0,
58 const Eigen::Vector3d& size1,
const Eigen::Isometry3d& T1,
62 const double& r0,
const Eigen::Isometry3d& c0,
63 const double& r1,
const Eigen::Isometry3d& c1,
67 CollisionObject* o1, CollisionObject* o2,
68 const double& cyl_rad,
const double& half_height,
69 const Eigen::Isometry3d& T0,
70 const double& sphere_rad,
const Eigen::Isometry3d& T1,
74 CollisionObject* o1, CollisionObject* o2,
75 const double& cyl_rad,
const double& half_height,
76 const Eigen::Isometry3d& T0,
77 const Eigen::Vector3d& plane_normal,
const Eigen::Isometry3d& T1,
CollisionResult * result
Collision result of DART.
Definition FCLCollisionDetector.cpp:157
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:1062
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:833
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:949
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:808
int collide(CollisionObject *o1, CollisionObject *o2, CollisionResult &result)
Definition DARTCollide.cpp:1253
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:1113
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:1181
Definition BulletCollisionDetector.cpp:63