|
int | addTriangles (BVHModel< BV > &model, const std::vector< Vector3< typename BV::S >> &points, const std::vector< Triangle > &tri_indices, FinalizeModel finalize_model) |
|
FCL_EXPORT void | axisFromEigen (const Matrix3< S > &eigenV, const Vector3< S > &eigenS, Matrix3< S > &axis) |
|
FCL_EXPORT void | axisFromEigen (const Matrix3< S > &eigenV, const Vector3< S > &eigenS, Transform3< S > &tf) |
|
template void | axisFromEigen (const Matrix3d &eigenV, const Vector3d &eigenS, Matrix3d &axis) |
|
template void | axisFromEigen (const Matrix3d &eigenV, const Vector3d &eigenS, Transform3d &tf) |
|
template Interval< double > | bound (const Interval< double > &i, const Interval< double > &other) |
|
template Interval< double > | bound (const Interval< double > &i, double v) |
|
FCL_EXPORT Interval< S > | bound (const Interval< S > &i, const Interval< S > &other) |
|
FCL_EXPORT Interval< S > | bound (const Interval< S > &i, S v) |
|
template IVector3< double > | bound (const IVector3< double > &i, const IVector3< double > &v) |
|
template IVector3< double > | bound (const IVector3< double > &i, const Vector3< double > &v) |
|
FCL_EXPORT IVector3< S > | bound (const IVector3< S > &i, const IVector3< S > &v) |
|
FCL_EXPORT IVector3< S > | bound (const IVector3< S > &i, const Vector3< S > &v) |
|
FCL_EXPORT void | BVHExpand (BVHModel< BV > &model, const Variance3< S > *ucs, S r) |
|
template void | BVHExpand (BVHModel< OBB< double >> &model, const Variance3< double > *ucs, double r) |
|
FCL_EXPORT void | BVHExpand (BVHModel< OBB< S >> &model, const Variance3< S > *ucs, S r=1.0) |
|
template void | BVHExpand (BVHModel< RSS< double >> &model, const Variance3< double > *ucs, double r) |
|
FCL_EXPORT void | BVHExpand (BVHModel< RSS< S >> &model, const Variance3< S > *ucs, S r=1.0) |
|
FCL_EXPORT void | circumCircleComputation (const Vector3< S > &a, const Vector3< S > &b, const Vector3< S > &c, Vector3< S > ¢er, S &radius) |
|
template void | circumCircleComputation (const Vector3d &a, const Vector3d &b, const Vector3d &c, Vector3d ¢er, double &radius) |
|
template void | clipToRange (double &val, double a, double b) |
|
FCL_EXPORT void | clipToRange (S &val, S a, S b) |
|
template FCL_EXPORT std::size_t | collide (const CollisionGeometry< double > *o1, const Transform3< double > &tf1, const CollisionGeometry< double > *o2, const Transform3< double > &tf2, const CollisionRequest< double > &request, CollisionResult< double > &result) |
|
FCL_EXPORT std::size_t | collide (const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const CollisionRequest< S > &request, CollisionResult< S > &result) |
|
FCL_EXPORT std::size_t | collide (const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const NarrowPhaseSolver *nsolver_, const CollisionRequest< S > &request, CollisionResult< S > &result) |
|
template FCL_EXPORT std::size_t | collide (const CollisionObject< double > *o1, const CollisionObject< double > *o2, const CollisionRequest< double > &request, CollisionResult< double > &result) |
|
FCL_EXPORT std::size_t | collide (const CollisionObject< S > *o1, const CollisionObject< S > *o2, const CollisionRequest< S > &request, CollisionResult< S > &result) |
|
FCL_EXPORT std::size_t | collide (const CollisionObject< S > *o1, const CollisionObject< S > *o2, const NarrowPhaseSolver *nsolver, const CollisionRequest< S > &request, CollisionResult< S > &result) |
|
template double | collide (const ContinuousCollisionObject< double > *o1, const ContinuousCollisionObject< double > *o2, const ContinuousCollisionRequest< double > &request, ContinuousCollisionResult< double > &result) |
|
FCL_EXPORT S | collide (const ContinuousCollisionObject< S > *o1, const ContinuousCollisionObject< S > *o2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
|
FCL_EXPORT VectorN< S, M+N > | combine (const VectorN< S, M > &v1, const VectorN< S, N > &v2) |
|
::testing::AssertionResult | CompareMatrices (const Eigen::MatrixBase< DerivedA > &m1, const Eigen::MatrixBase< DerivedB > &m2, double tolerance=0.0, MatrixCompareType compare_type=MatrixCompareType::absolute) |
|
template bool | comparePenDepth (const ContactPoint< double > &_cp1, const ContactPoint< double > &_cp2) |
|
FCL_EXPORT bool | comparePenDepth (const ContactPoint< S > &_cp1, const ContactPoint< S > &_cp2) |
|
FCL_EXPORT void | computeBV (const Shape &s, const Transform3< typename BV::S > &tf, BV &bv) |
|
template void | computeVertices (const OBB< double > &b, Vector3< double > vertices[8]) |
|
FCL_EXPORT void | computeVertices (const OBB< S > &b, Vector3< S > vertices[8]) |
|
template void | constructBox (const AABB< double > &bv, Box< double > &box, Transform3< double > &tf) |
|
template void | constructBox (const AABB< double > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
|
FCL_EXPORT void | constructBox (const AABB< S > &bv, Box< S > &box, Transform3< S > &tf) |
|
FCL_EXPORT void | constructBox (const AABB< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
|
template void | constructBox (const KDOP< double, 16 > &bv, Box< double > &box, Transform3< double > &tf) |
|
template void | constructBox (const KDOP< double, 16 > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
|
template void | constructBox (const KDOP< double, 18 > &bv, Box< double > &box, Transform3< double > &tf) |
|
template void | constructBox (const KDOP< double, 18 > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
|
template void | constructBox (const KDOP< double, 24 > &bv, Box< double > &box, Transform3< double > &tf) |
|
template void | constructBox (const KDOP< double, 24 > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
|
FCL_EXPORT void | constructBox (const KDOP< S, 16 > &bv, Box< S > &box, Transform3< S > &tf) |
|
FCL_EXPORT void | constructBox (const KDOP< S, 16 > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
|
FCL_EXPORT void | constructBox (const KDOP< S, 18 > &bv, Box< S > &box, Transform3< S > &tf) |
|
FCL_EXPORT void | constructBox (const KDOP< S, 18 > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
|
FCL_EXPORT void | constructBox (const KDOP< S, 24 > &bv, Box< S > &box, Transform3< S > &tf) |
|
FCL_EXPORT void | constructBox (const KDOP< S, 24 > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
|
template void | constructBox (const kIOS< double > &bv, Box< double > &box, Transform3< double > &tf) |
|
template void | constructBox (const kIOS< double > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
|
FCL_EXPORT void | constructBox (const kIOS< S > &bv, Box< S > &box, Transform3< S > &tf) |
|
FCL_EXPORT void | constructBox (const kIOS< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
|
template void | constructBox (const OBB< double > &bv, Box< double > &box, Transform3< double > &tf) |
|
template void | constructBox (const OBB< double > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
|
FCL_EXPORT void | constructBox (const OBB< S > &bv, Box< S > &box, Transform3< S > &tf) |
|
FCL_EXPORT void | constructBox (const OBB< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
|
template void | constructBox (const OBBRSS< double > &bv, Box< double > &box, Transform3< double > &tf) |
|
template void | constructBox (const OBBRSS< double > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
|
FCL_EXPORT void | constructBox (const OBBRSS< S > &bv, Box< S > &box, Transform3< S > &tf) |
|
FCL_EXPORT void | constructBox (const OBBRSS< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
|
template void | constructBox (const RSS< double > &bv, Box< double > &box, Transform3< double > &tf) |
|
template void | constructBox (const RSS< double > &bv, const Transform3< double > &tf_bv, Box< double > &box, Transform3< double > &tf) |
|
FCL_EXPORT void | constructBox (const RSS< S > &bv, Box< S > &box, Transform3< S > &tf) |
|
FCL_EXPORT void | constructBox (const RSS< S > &bv, const Transform3< S > &tf_bv, Box< S > &box, Transform3< S > &tf) |
|
template double | continuousCollide (const CollisionGeometry< double > *o1, const MotionBase< double > *motion1, const CollisionGeometry< double > *o2, const MotionBase< double > *motion2, const ContinuousCollisionRequest< double > &request, ContinuousCollisionResult< double > &result) |
|
template double | continuousCollide (const CollisionGeometry< double > *o1, const Transform3< double > &tf1_beg, const Transform3< double > &tf1_end, const CollisionGeometry< double > *o2, const Transform3< double > &tf2_beg, const Transform3< double > &tf2_end, const ContinuousCollisionRequest< double > &request, ContinuousCollisionResult< double > &result) |
|
FCL_EXPORT S | continuousCollide (const CollisionGeometry< S > *o1, const MotionBase< S > *motion1, const CollisionGeometry< S > *o2, const MotionBase< S > *motion2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
|
FCL_EXPORT S | continuousCollide (const CollisionGeometry< S > *o1, const Transform3< S > &tf1_beg, const Transform3< S > &tf1_end, const CollisionGeometry< S > *o2, const Transform3< S > &tf2_beg, const Transform3< S > &tf2_end, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
|
template double | continuousCollide (const CollisionObject< double > *o1, const Transform3< double > &tf1_end, const CollisionObject< double > *o2, const Transform3< double > &tf2_end, const ContinuousCollisionRequest< double > &request, ContinuousCollisionResult< double > &result) |
|
FCL_EXPORT S | continuousCollide (const CollisionObject< S > *o1, const Transform3< S > &tf1_end, const CollisionObject< S > *o2, const Transform3< S > &tf2_end, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
|
FCL_EXPORT S | continuousCollideBVHPolynomial (const CollisionGeometry< S > *o1, const TranslationMotion< S > *motion1, const CollisionGeometry< S > *o2, const TranslationMotion< S > *motion2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
|
FCL_EXPORT S | continuousCollideConservativeAdvancement (const CollisionGeometry< S > *o1, const MotionBase< S > *motion1, const CollisionGeometry< S > *o2, const MotionBase< S > *motion2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
|
FCL_EXPORT S | continuousCollideNaive (const CollisionGeometry< S > *o1, const MotionBase< S > *motion1, const CollisionGeometry< S > *o2, const MotionBase< S > *motion2, const ContinuousCollisionRequest< S > &request, ContinuousCollisionResult< S > &result) |
|
FCL_EXPORT void | convertBV (const BV1 &bv1, const Transform3< typename BV1::S > &tf1, BV2 &bv2) |
|
bool | DefaultCollisionFunction (CollisionObject< S > *o1, CollisionObject< S > *o2, void *data) |
|
bool | DefaultContinuousCollisionFunction (ContinuousCollisionObject< S > *o1, ContinuousCollisionObject< S > *o2, void *data) |
|
bool | DefaultDistanceFunction (CollisionObject< S > *o1, CollisionObject< S > *o2, void *data, S &dist) |
|
template double | distance (const CollisionGeometry< double > *o1, const Transform3< double > &tf1, const CollisionGeometry< double > *o2, const Transform3< double > &tf2, const DistanceRequest< double > &request, DistanceResult< double > &result) |
|
FCL_EXPORT S | distance (const CollisionGeometry< S > *o1, const Transform3< S > &tf1, const CollisionGeometry< S > *o2, const Transform3< S > &tf2, const DistanceRequest< S > &request, DistanceResult< S > &result) |
|
NarrowPhaseSolver::S | distance (const CollisionGeometry< typename NarrowPhaseSolver::S > *o1, const Transform3< typename NarrowPhaseSolver::S > &tf1, const CollisionGeometry< typename NarrowPhaseSolver::S > *o2, const Transform3< typename NarrowPhaseSolver::S > &tf2, const NarrowPhaseSolver *nsolver_, const DistanceRequest< typename NarrowPhaseSolver::S > &request, DistanceResult< typename NarrowPhaseSolver::S > &result) |
|
template double | distance (const CollisionObject< double > *o1, const CollisionObject< double > *o2, const DistanceRequest< double > &request, DistanceResult< double > &result) |
|
FCL_EXPORT S | distance (const CollisionObject< S > *o1, const CollisionObject< S > *o2, const DistanceRequest< S > &request, DistanceResult< S > &result) |
|
NarrowPhaseSolver::S | distance (const CollisionObject< typename NarrowPhaseSolver::S > *o1, const CollisionObject< typename NarrowPhaseSolver::S > *o2, const NarrowPhaseSolver *nsolver, const DistanceRequest< typename NarrowPhaseSolver::S > &request, DistanceResult< typename NarrowPhaseSolver::S > &result) |
|
S | distance (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q) |
|
S | distance (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const OBBRSS< S > &b1, const OBBRSS< S > &b2, Vector3< S > *P, Vector3< S > *Q) |
|
S | distance (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const RSS< S > &b1, const RSS< S > &b2, Vector3< S > *P, Vector3< S > *Q) |
|
S | distance (const Transform3< S > &tf, const kIOS< S > &b1, const kIOS< S > &b2, Vector3< S > *P, Vector3< S > *Q) |
|
FCL_EXPORT S | distance (const Transform3< S > &tf, const OBBRSS< S > &b1, const OBBRSS< S > &b2, Vector3< S > *P=nullptr, Vector3< S > *Q=nullptr) |
|
FCL_EXPORT void | eigen (const Matrix3< S > &m, Vector3< S > &dout, Matrix3< S > &vout) |
|
template void | eigen (const Matrix3d &m, Vector3d &dout, Matrix3d &vout) |
|
FCL_EXPORT void | eigen_old (const Matrix3< S > &m, Vector3< S > &dout, Matrix3< S > &vout) |
|
template void | eigen_old (const Matrix3d &m, Vector3d &dout, Matrix3d &vout) |
|
FCL_EXPORT void | fit (const Vector3< typename BV::S > *const ps, int n, BV &bv) |
|
template void | flipNormal (std::vector< ContactPoint< double >> &contacts) |
|
FCL_EXPORT void | flipNormal (std::vector< ContactPoint< S >> &contacts) |
|
int | generateBVHModel (BVHModel< BV > &model, const Box< typename BV::S > &shape, const Transform3< typename BV::S > &pose, FinalizeModel finalize_model=FinalizeModel::DO) |
|
int | generateBVHModel (BVHModel< BV > &model, const Cone< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int circle_split_tot, unsigned int h_num, FinalizeModel finalize_model=FinalizeModel::DO) |
|
int | generateBVHModel (BVHModel< BV > &model, const Cone< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int circle_split_tot_for_unit_cone, FinalizeModel finalize_model=FinalizeModel::DO) |
|
int | generateBVHModel (BVHModel< BV > &model, const Cylinder< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int circle_split_tot, unsigned int h_num, FinalizeModel finalize_model=FinalizeModel::DO) |
|
int | generateBVHModel (BVHModel< BV > &model, const Cylinder< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int circle_split_tot_for_unit_cylinder, FinalizeModel finalize_model=FinalizeModel::DO) |
|
int | generateBVHModel (BVHModel< BV > &model, const Ellipsoid< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int n_faces_for_unit_ellipsoid, FinalizeModel finalize_model=FinalizeModel::DO) |
|
int | generateBVHModel (BVHModel< BV > &model, const Ellipsoid< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int seg, unsigned int ring, FinalizeModel finalize_model=FinalizeModel::DO) |
|
int | generateBVHModel (BVHModel< BV > &model, const Sphere< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int n_faces_for_unit_sphere, FinalizeModel finalize_model=FinalizeModel::DO) |
|
int | generateBVHModel (BVHModel< BV > &model, const Sphere< typename BV::S > &shape, const Transform3< typename BV::S > &pose, unsigned int seg, unsigned int ring, FinalizeModel finalize_model=FinalizeModel::DO) |
|
FCL_EXPORT Matrix3< S > | generateCoordinateSystem (const Vector3< S > &x_axis) |
|
template Matrix3d | generateCoordinateSystem (const Vector3d &x_axis) |
|
template void | generateTaylorModelForCosFunc (TaylorModel< double > &tm, double w, double q0) |
|
FCL_EXPORT void | generateTaylorModelForCosFunc (TaylorModel< S > &tm, S w, S q0) |
|
template void | generateTaylorModelForLinearFunc (TaylorModel< double > &tm, double p, double v) |
|
FCL_EXPORT void | generateTaylorModelForLinearFunc (TaylorModel< S > &tm, S p, S v) |
|
template void | generateTaylorModelForSinFunc (TaylorModel< double > &tm, double w, double q0) |
|
FCL_EXPORT void | generateTaylorModelForSinFunc (TaylorModel< S > &tm, S w, S q0) |
|
template void | generateTVector3ForLinearFunc (TVector3< double > &v, const Vector3< double > &position, const Vector3< double > &velocity) |
|
FCL_EXPORT void | generateTVector3ForLinearFunc (TVector3< S > &v, const Vector3< S > &position, const Vector3< S > &velocity) |
|
detail::CollisionFunctionMatrix< GJKSolver > & | getCollisionFunctionLookTable () |
|
detail::ConservativeAdvancementFunctionMatrix< GJKSolver > & | getConservativeAdvancementFunctionLookTable () |
|
FCL_EXPORT void | getCovariance (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, Matrix3< S > &M) |
|
template void | getCovariance (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, Matrix3d &M) |
|
detail::DistanceFunctionMatrix< GJKSolver > & | getDistanceFunctionLookTable () |
|
FCL_EXPORT void | getDistances (const Vector3< S > &p, S *d) |
|
template void | getDistances< double, 5 > (const Vector3< double > &p, double *d) |
|
template void | getDistances< double, 6 > (const Vector3< double > &p, double *d) |
|
template void | getDistances< double, 9 > (const Vector3< double > &p, double *d) |
|
FCL_EXPORT void | getExtentAndCenter (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3< S > &axis, Vector3< S > ¢er, Vector3< S > &extent) |
|
FCL_EXPORT void | getExtentAndCenter (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, Transform3< S > &tf, Vector3< S > &extent) |
|
template void | getExtentAndCenter (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3d &axis, Vector3d ¢er, Vector3d &extent) |
|
FCL_EXPORT MotionBasePtr< S > | getMotionBase (const Transform3< S > &tf_beg, const Transform3< S > &tf_end, CCDMotionType motion_type) |
|
FCL_EXPORT void | getRadiusAndOriginAndRectangleSize (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3< S > &axis, Vector3< S > &origin, S l[2], S &r) |
|
FCL_EXPORT void | getRadiusAndOriginAndRectangleSize (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, Transform3< S > &tf, S l[2], S &r) |
|
template void | getRadiusAndOriginAndRectangleSize (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3d &axis, Vector3d &origin, double l[2], double &r) |
|
template void | getRadiusAndOriginAndRectangleSize (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, Transform3d &tf, double l[2], double &r) |
|
FCL_EXPORT void | hat (Matrix3< S > &mat, const Vector3< S > &vec) |
|
template void | hat (Matrix3d &mat, const Vector3d &vec) |
|
template bool | inVoronoi (double a, double b, double Anorm_dot_B, double Anorm_dot_T, double A_dot_B, double A_dot_T, double B_dot_T) |
|
FCL_EXPORT bool | inVoronoi (S a, S b, S Anorm_dot_B, S Anorm_dot_T, S A_dot_B, S A_dot_T, S B_dot_T) |
|
std::shared_ptr< _Tp > | make_aligned_shared (_Args &&... __args) |
|
FCL_EXPORT S | maximumDistance (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Vector3< S > &query) |
|
template double | maximumDistance (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Vector3d &query) |
|
template OBB< double > | merge_largedist (const OBB< double > &b1, const OBB< double > &b2) |
|
FCL_EXPORT OBB< S > | merge_largedist (const OBB< S > &b1, const OBB< S > &b2) |
|
template OBB< double > | merge_smalldist (const OBB< double > &b1, const OBB< double > &b2) |
|
FCL_EXPORT OBB< S > | merge_smalldist (const OBB< S > &b1, const OBB< S > &b2) |
|
template void | minmax (double a, double b, double &minv, double &maxv) |
|
template void | minmax (double p, double &minv, double &maxv) |
|
FCL_EXPORT void | minmax (S a, S b, S &minv, S &maxv) |
|
FCL_EXPORT void | minmax (S p, S &minv, S &maxv) |
|
FCL_EXPORT void | normalize (Vector3< S > &v, bool *signal) |
|
template void | normalize (Vector3d &v, bool *signal) |
|
template bool | obbDisjoint (const Matrix3< double > &B, const Vector3< double > &T, const Vector3< double > &a, const Vector3< double > &b) |
|
FCL_EXPORT bool | obbDisjoint (const Matrix3< S > &B, const Vector3< S > &T, const Vector3< S > &a, const Vector3< S > &b) |
|
template bool | obbDisjoint (const Transform3< double > &tf, const Vector3< double > &a, const Vector3< double > &b) |
|
FCL_EXPORT bool | obbDisjoint (const Transform3< S > &tf, const Vector3< S > &a, const Vector3< S > &b) |
|
template TMatrix3< double > | operator* (const Matrix3< double > &m, const TaylorModel< double > &a) |
|
FCL_EXPORT TMatrix3< S > | operator* (const Matrix3< S > &m, const TaylorModel< S > &a) |
|
template TMatrix3< double > | operator* (const TaylorModel< double > &a, const Matrix3< double > &m) |
|
template TMatrix3< double > | operator* (const TaylorModel< double > &a, const TMatrix3< double > &m) |
|
FCL_EXPORT TMatrix3< S > | operator* (const TaylorModel< S > &a, const Matrix3< S > &m) |
|
FCL_EXPORT TMatrix3< S > | operator* (const TaylorModel< S > &a, const TMatrix3< S > &m) |
|
template TVector3< double > | operator* (const Vector3< double > &v, const TaylorModel< double > &a) |
|
FCL_EXPORT TVector3< S > | operator* (const Vector3< S > &v, const TaylorModel< S > &a) |
|
template TaylorModel< double > | operator* (double d, const TaylorModel< double > &a) |
|
template TMatrix3< double > | operator* (double d, const TMatrix3< double > &m) |
|
FCL_EXPORT TaylorModel< S > | operator* (S d, const TaylorModel< S > &a) |
|
FCL_EXPORT TMatrix3< S > | operator* (S d, const TMatrix3< S > &m) |
|
template TMatrix3< double > | operator+ (const Matrix3< double > &m1, const TMatrix3< double > &m2) |
|
FCL_EXPORT TMatrix3< S > | operator+ (const Matrix3< S > &m1, const TMatrix3< S > &m2) |
|
template TVector3< double > | operator+ (const Vector3< double > &v1, const TVector3< double > &v2) |
|
FCL_EXPORT TVector3< S > | operator+ (const Vector3< S > &v1, const TVector3< S > &v2) |
|
template TaylorModel< double > | operator+ (double d, const TaylorModel< double > &a) |
|
FCL_EXPORT TaylorModel< S > | operator+ (S d, const TaylorModel< S > &a) |
|
template TMatrix3< double > | operator- (const Matrix3< double > &m1, const TMatrix3< double > &m2) |
|
FCL_EXPORT TMatrix3< S > | operator- (const Matrix3< S > &m1, const TMatrix3< S > &m2) |
|
template TVector3< double > | operator- (const Vector3< double > &v1, const TVector3< double > &v2) |
|
FCL_EXPORT TVector3< S > | operator- (const Vector3< S > &v1, const TVector3< S > &v2) |
|
template TaylorModel< double > | operator- (double d, const TaylorModel< double > &a) |
|
FCL_EXPORT TaylorModel< S > | operator- (S d, const TaylorModel< S > &a) |
|
std::ostream & | operator<< (std::ostream &out, const NODE_TYPE &node) |
|
FCL_EXPORT bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const kIOS< S > &b1, const kIOS< S > &b2) |
|
FCL_EXPORT bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const OBB< S > &b1, const OBB< S > &b2) |
|
FCL_EXPORT bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const OBBRSS< S > &b1, const OBBRSS< S > &b2) |
|
FCL_EXPORT bool | overlap (const Eigen::MatrixBase< DerivedA > &R0, const Eigen::MatrixBase< DerivedB > &T0, const RSS< S > &b1, const RSS< S > &b2) |
|
FCL_EXPORT bool | overlap (const Transform3< S > &tf, const kIOS< S > &b1, const kIOS< S > &b2) |
|
FCL_EXPORT bool | overlap (const Transform3< S > &tf, const OBBRSS< S > &b1, const OBBRSS< S > &b2) |
|
template double | rectDistance (const Matrix3< double > &Rab, const Vector3< double > &Tab, const double a[2], const double b[2], Vector3< double > *P, Vector3< double > *Q) |
|
FCL_EXPORT S | rectDistance (const Matrix3< S > &Rab, const Vector3< S > &Tab, const S a[2], const S b[2], Vector3< S > *P=nullptr, Vector3< S > *Q=nullptr) |
|
template double | rectDistance (const Transform3< double > &tfab, const double a[2], const double b[2], Vector3< double > *P, Vector3< double > *Q) |
|
S | rectDistance (const Transform3< S > &tfab, const S a[2], const S b[2], Vector3< S > *P, Vector3< S > *Q) |
|
FCL_EXPORT void | relativeTransform (const Eigen::MatrixBase< DerivedA > &R1, const Eigen::MatrixBase< DerivedB > &t1, const Eigen::MatrixBase< DerivedA > &R2, const Eigen::MatrixBase< DerivedB > &t2, Eigen::MatrixBase< DerivedC > &R, Eigen::MatrixBase< DerivedD > &t) |
|
FCL_EXPORT void | relativeTransform (const Eigen::Transform< S, 3, Eigen::Isometry > &T1, const Eigen::Transform< S, 3, Eigen::Isometry > &T2, Eigen::MatrixBase< DerivedA > &R, Eigen::MatrixBase< DerivedB > &t) |
|
FCL_EXPORT void | relativeTransform (const Transform3< S > &T1, const Transform3< S > &T2, Eigen::MatrixBase< DerivedA > &R, Eigen::MatrixBase< DerivedB > &t) |
|
template IMatrix3< double > | rotationConstrain (const IMatrix3< double > &m) |
|
FCL_EXPORT IMatrix3< S > | rotationConstrain (const IMatrix3< S > &m) |
|
template TMatrix3< double > | rotationConstrain (const TMatrix3< double > &m) |
|
FCL_EXPORT TMatrix3< S > | rotationConstrain (const TMatrix3< S > &m) |
|
template void | segCoords (double &t, double &u, double a, double b, double A_dot_B, double A_dot_T, double B_dot_T) |
|
FCL_EXPORT void | segCoords (S &t, S &u, S a, S b, S A_dot_B, S A_dot_T, S B_dot_T) |
|
template Halfspace< double > | transform (const Halfspace< double > &a, const Transform3< double > &tf) |
|
FCL_EXPORT Halfspace< S > | transform (const Halfspace< S > &a, const Transform3< S > &tf) |
|
template Plane< double > | transform (const Plane< double > &a, const Transform3< double > &tf) |
|
FCL_EXPORT Plane< S > | transform (const Plane< S > &a, const Transform3< S > &tf) |
|
AABB< S > | translate (const AABB< S > &aabb, const Eigen::MatrixBase< Derived > &t) |
|
FCL_EXPORT KDOP< S, N > | translate (const KDOP< S, N > &bv, const Eigen::MatrixBase< Derived > &t) |
|
FCL_EXPORT kIOS< S > | translate (const kIOS< S > &bv, const Eigen::MatrixBase< Derived > &t) |
|
FCL_EXPORT OBB< S > | translate (const OBB< S > &bv, const Eigen::MatrixBase< Derived > &t) |
|
template OBBRSS< double > | translate (const OBBRSS< double > &bv, const Vector3< double > &t) |
|
FCL_EXPORT OBBRSS< S > | translate (const OBBRSS< S > &bv, const Vector3< S > &t) |
|
template RSS< double > | translate (const RSS< double > &bv, const Vector3< double > &t) |
|
FCL_EXPORT RSS< S > | translate (const RSS< S > &bv, const Vector3< S > &t) |
|
FCL_EXPORT Derived::RealScalar | triple (const Eigen::MatrixBase< Derived > &x, const Eigen::MatrixBase< Derived > &y, const Eigen::MatrixBase< Derived > &z) |
|