46 #ifdef COAL_HAS_DOXYGEN_AUTODOC
47 #include "doxygen_autodoc/coal/math/transform.h"
58 if (i >= 3 || i <= -3)
59 PyErr_SetString(PyExc_IndexError,
"Index out of range");
63 if (i >= 3 || i <= -3)
64 PyErr_SetString(PyExc_IndexError,
"Index out of range");
72 if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::Quaterniond>())
74 if (!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
77 eigenpy::enableEigenPySpecific<Matrix3s>();
78 eigenpy::enableEigenPySpecific<Vec3s>();
80 class_<Transform3s>(
"Transform3s", doxygen::class_doc<Transform3s>(), no_init)
81 .def(dv::init<Transform3s>())
82 .def(dv::init<
Transform3s,
const Matrix3s::MatrixBase&,
83 const Vec3s::MatrixBase&>())
84 .def(dv::init<Transform3s, const Quatf&, const Vec3s::MatrixBase&>())
85 .def(dv::init<Transform3s, const Matrix3s&>())
86 .def(dv::init<Transform3s, const Quatf&>())
87 .def(dv::init<Transform3s, const Vec3s&>())
88 .def(dv::init<Transform3s, const Transform3s&>())
91 .def(
"getTranslation", &Transform3s::getTranslation,
93 return_value_policy<copy_const_reference>())
94 .def(
"getRotation", &Transform3s::getRotation,
95 return_value_policy<copy_const_reference>())
96 .def(
"isIdentity", &Transform3s::isIdentity,
98 bp::arg(
"prec") = Eigen::NumTraits<CoalScalar>::dummy_precision()),
101 .def(
dv::member_func(
"setQuatRotation", &Transform3s::setQuatRotation))
102 .def(
"setTranslation", &Transform3s::setTranslation<Vec3s>)
103 .def(
"setRotation", &Transform3s::setRotation<Matrix3s>)
105 &Transform3s::setTransform<Matrix3s, Vec3s>))
109 &Transform3s::setTransform)))
112 .staticmethod(
"Identity")
116 .staticmethod(
"Random")
119 .def(
"inverseInPlace", &Transform3s::inverseInPlace,
120 return_internal_reference<>(),
132 class_<Triangle>(
"Triangle", no_init)
133 .def(dv::init<Triangle>())
140 .staticmethod(
"size")
144 std::vector<Vec3s> >()) {
145 class_<std::vector<Vec3s> >(
"StdVec_Vec3s")
146 .
def(vector_indexing_suite<std::vector<Vec3s> >());
149 std::vector<Triangle> >()) {
150 class_<std::vector<Triangle> >(
"StdVec_Triangle")
151 .
def(vector_indexing_suite<std::vector<Triangle> >());