43 #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC 44 #include "doxygen_autodoc/hpp/fcl/math/transform.h" 54 if (i >= 3 || i <= -3)
55 PyErr_SetString(PyExc_IndexError,
"Index out of range");
59 if (i >= 3 || i <= -3)
60 PyErr_SetString(PyExc_IndexError,
"Index out of range");
68 if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::Quaterniond>())
70 if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
73 eigenpy::enableEigenPySpecific<Matrix3f>();
74 eigenpy::enableEigenPySpecific<Vec3f>();
76 class_<Transform3f>(
"Transform3f", doxygen::class_doc<Transform3f>(), no_init)
77 .def(dv::init<Transform3f>())
78 .def(dv::init<
Transform3f,
const Matrix3f::MatrixBase&,
79 const Vec3f::MatrixBase&>())
81 const Vec3f::MatrixBase&>())
82 .def(dv::init<Transform3f, const Matrix3f&>())
83 .def(dv::init<Transform3f, const Quaternion3f&>())
84 .def(dv::init<Transform3f, const Vec3f&>())
85 .def(dv::init<Transform3f, const Transform3f&>())
88 .def(
"getTranslation", &Transform3f::getTranslation,
90 return_value_policy<copy_const_reference>())
91 .def(
"getRotation", &Transform3f::getRotation,
92 return_value_policy<copy_const_reference>())
93 .def(
"isIdentity", &Transform3f::isIdentity,
95 bp::arg(
"prec") = Eigen::NumTraits<FCL_REAL>::dummy_precision()),
99 .def(
"setTranslation", &Transform3f::setTranslation<Vec3f>)
100 .def(
"setRotation", &Transform3f::setRotation<Matrix3f>)
102 &Transform3f::setTransform<Matrix3f, Vec3f>))
106 &Transform3f::setTransform)))
109 .staticmethod(
"Identity")
112 .def(
"inverseInPlace", &Transform3f::inverseInPlace,
113 return_internal_reference<>(),
123 class_<Triangle>(
"Triangle", no_init)
124 .
def(dv::init<Triangle>())
131 .staticmethod(
"size")
135 std::vector<Vec3f> >()) {
136 class_<std::vector<Vec3f> >(
"StdVec_Vec3f")
137 .
def(vector_indexing_suite<std::vector<Vec3f> >());
140 std::vector<Triangle> >()) {
141 class_<std::vector<Triangle> >(
"StdVec_Triangle")
142 .
def(vector_indexing_suite<std::vector<Triangle> >());
const char * member_func_doc(FuncPtr)
void EIGENPY_DLLAPI exposeQuaternion()
static Triangle::index_type getitem(const Triangle &t, int i)
void def(const char *name, Func func)
void EIGENPY_DLLAPI enableEigenPy()
bool register_symbolic_link_to_registered_type()
Eigen::Quaternion< FCL_REAL > Quaternion3f
Triangle with 3 indices for points.
static void setitem(Triangle &t, int i, Triangle::index_type v)
member_func_impl< function_type > member_func(const char *name, const function_type &function)
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
void EIGENPY_DLLAPI exposeAngleAxis()