Namespaces | Functions
geometry-inl.h File Reference
#include "fcl/math/geometry.h"
#include "fcl/math/constants.h"
Include dependency graph for geometry-inl.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 fcl
 Main namespace.
 
 fcl::detail
 

Functions

template<typename S >
FCL_EXPORT void fcl::axisFromEigen (const Matrix3< S > &eigenV, const Vector3< S > &eigenS, Matrix3< S > &axis)
 
template<typename S >
FCL_EXPORT void fcl::axisFromEigen (const Matrix3< S > &eigenV, const Vector3< S > &eigenS, Transform3< S > &tf)
 
template void fcl::axisFromEigen (const Matrix3d &eigenV, const Vector3d &eigenS, Matrix3d &axis)
 
template void fcl::axisFromEigen (const Matrix3d &eigenV, const Vector3d &eigenS, Transform3d &tf)
 
template<typename S >
FCL_EXPORT void fcl::circumCircleComputation (const Vector3< S > &a, const Vector3< S > &b, const Vector3< S > &c, Vector3< S > &center, S &radius)
 Compute the center and radius for a triangle's circumcircle. More...
 
template void fcl::circumCircleComputation (const Vector3d &a, const Vector3d &b, const Vector3d &c, Vector3d &center, double &radius)
 
template<typename S , int M, int N>
FCL_EXPORT VectorN< S, M+N > fcl::combine (const VectorN< S, M > &v1, const VectorN< S, N > &v2)
 
template<typename S >
FCL_EXPORT void fcl::eigen (const Matrix3< S > &m, Vector3< S > &dout, Matrix3< S > &vout)
 compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors More...
 
template void fcl::eigen (const Matrix3d &m, Vector3d &dout, Matrix3d &vout)
 
template<typename S >
FCL_EXPORT void fcl::eigen_old (const Matrix3< S > &m, Vector3< S > &dout, Matrix3< S > &vout)
 compute the eigen vector and eigen vector of a matrix. dout is the eigen values, vout is the eigen vectors More...
 
template void fcl::eigen_old (const Matrix3d &m, Vector3d &dout, Matrix3d &vout)
 
template<typename S >
FCL_EXPORT Matrix3< S > fcl::generateCoordinateSystem (const Vector3< S > &x_axis)
 compute orthogonal coordinate system basis with given x-axis. More...
 
template Matrix3d fcl::generateCoordinateSystem (const Vector3d &x_axis)
 
template<typename S >
FCL_EXPORT void fcl::getCovariance (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, Matrix3< S > &M)
 Compute the covariance matrix for a set or subset of points. if ts = null, then indices refer to points directly; otherwise refer to triangles. More...
 
template void fcl::getCovariance (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, Matrix3d &M)
 
template<typename S >
FCL_EXPORT void fcl::getExtentAndCenter (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3< S > &axis, Vector3< S > &center, Vector3< S > &extent)
 Compute the bounding volume extent and center for a set or subset of points, given the BV axises. More...
 
template void fcl::getExtentAndCenter (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3d &axis, Vector3d &center, Vector3d &extent)
 
template<typename S >
FCL_EXPORT void fcl::detail::getExtentAndCenter_mesh (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3< S > &axis, Vector3< S > &center, Vector3< S > &extent)
 Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known. More...
 
template void fcl::detail::getExtentAndCenter_mesh (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Matrix3d &axis, Vector3d &center, Vector3d &extent)
 
template<typename S >
FCL_EXPORT void fcl::detail::getExtentAndCenter_pointcloud (const Vector3< S > *const ps, const Vector3< S > *const ps2, unsigned int *indices, int n, const Matrix3< S > &axis, Vector3< S > &center, Vector3< S > &extent)
 Compute the bounding volume extent and center for a set or subset of points. The bounding volume axes are known. More...
 
template void fcl::detail::getExtentAndCenter_pointcloud (const Vector3d *const ps, const Vector3d *const ps2, unsigned int *indices, int n, const Matrix3d &axis, Vector3d &center, Vector3d &extent)
 
template<typename S >
FCL_EXPORT void fcl::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)
 Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises. More...
 
template<typename S >
FCL_EXPORT void fcl::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)
 Compute the RSS bounding volume parameters: radius, rectangle size and the origin, given the BV axises. More...
 
template void fcl::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 fcl::getRadiusAndOriginAndRectangleSize (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, Transform3d &tf, double l[2], double &r)
 
template<typename S >
FCL_EXPORT void fcl::hat (Matrix3< S > &mat, const Vector3< S > &vec)
 
template void fcl::hat (Matrix3d &mat, const Vector3d &vec)
 
template<typename S >
FCL_EXPORT S fcl::maximumDistance (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Vector3< S > &query)
 Compute the maximum distance from a given center point to a point cloud. More...
 
template double fcl::maximumDistance (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Vector3d &query)
 
template<typename S >
FCL_EXPORT S fcl::detail::maximumDistance_mesh (const Vector3< S > *const ps, const Vector3< S > *const ps2, Triangle *ts, unsigned int *indices, int n, const Vector3< S > &query)
 
template double fcl::detail::maximumDistance_mesh (const Vector3d *const ps, const Vector3d *const ps2, Triangle *ts, unsigned int *indices, int n, const Vector3d &query)
 
template<typename S >
FCL_EXPORT S fcl::detail::maximumDistance_pointcloud (const Vector3< S > *const ps, const Vector3< S > *const ps2, unsigned int *indices, int n, const Vector3< S > &query)
 
template double fcl::detail::maximumDistance_pointcloud (const Vector3d *const ps, const Vector3d *const ps2, unsigned int *indices, int n, const Vector3d &query)
 
template<typename S >
FCL_EXPORT void fcl::normalize (Vector3< S > &v, bool *signal)
 
template void fcl::normalize (Vector3d &v, bool *signal)
 
template<typename DerivedA , typename DerivedB , typename DerivedC , typename DerivedD >
FCL_EXPORT void fcl::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)
 
template<typename S , typename DerivedA , typename DerivedB >
FCL_EXPORT void fcl::relativeTransform (const Transform3< S > &T1, const Transform3< S > &T2, Eigen::MatrixBase< DerivedA > &R, Eigen::MatrixBase< DerivedB > &t)
 
template<typename Derived >
FCL_EXPORT Derived::RealScalar fcl::triple (const Eigen::MatrixBase< Derived > &x, const Eigen::MatrixBase< Derived > &y, const Eigen::MatrixBase< Derived > &z)
 


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:49