7 #include "pinocchio/multibody/fwd.hpp" 8 #include "pinocchio/utils/version.hpp" 19 #include <Eigen/Geometry> 27 bp::docstring_options module_docstring_options(
true,
true,
false);
30 bp::scope().attr(
"__raw_version__") = bp::str(PINOCCHIO_VERSION);
34 bp::import(
"warnings");
36 if(! register_symbolic_link_to_registered_type<Eigen::Quaterniond>())
38 if(! register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
43 typedef Eigen::Matrix<double,6,6> Matrix6d;
44 typedef Eigen::Matrix<double,6,1> Vector6d;
45 typedef Eigen::Matrix<double,6,Eigen::Dynamic>
Matrix6x;
46 typedef Eigen::Matrix<double,3,Eigen::Dynamic> Matrix3x;
48 eigenpy::enableEigenPySpecific<Matrix6d>();
49 eigenpy::enableEigenPySpecific<Vector6d>();
50 eigenpy::enableEigenPySpecific<Matrix6x>();
51 eigenpy::enableEigenPySpecific<Matrix3x>();
63 bp::enum_< ::pinocchio::ReferenceFrame >(
"ReferenceFrame")
70 bp::enum_< ::pinocchio::KinematicLevel >(
"KinematicLevel")
77 bp::enum_< ::pinocchio::ArgumentPosition>(
"ArgumentPosition")
95 #ifdef PINOCCHIO_PYTHON_INTERFACE_WITH_HPP_FCL_PYTHON_BINDINGS 97 #endif // PINOCCHIO_PYTHON_INTERFACE_WITH_HPP_FCL_PYTHON_BINDINGS 99 #ifdef PINOCCHIO_PYTHON_INTERFACE_WITH_OPENMP The WORLD frame convention corresponds to the frame concident with the Universe/Inertial frame but mo...
void EIGENPY_DLLAPI exposeQuaternion()
Refers to the quantities related to the 2nd-order kinematics (joint accelerations, center of mass acceleration, etc.).
void exposeSerialization()
void exposeParallelAlgorithms()
Register the conversion from a Python list to a std::vector.
void EIGENPY_DLLAPI enableEigenPy()
BOOST_PYTHON_MODULE(pinocchio_pywrap)
The LOCAL frame convention corresponds to the frame directly attached to the moving part (Joint...
std::string printVersion(const std::string &delimiter=".")
Returns the current version of Pinocchio as a string using the following standard: PINOCCHIO_MINOR_VE...
Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
Refers to the quantities related to the 1st-order kinematics (joint velocities, center of mass veloci...
void exposeDependencies()
The LOCAL_WORLD_ALIGNED frame convention corresponds to the frame centered on the moving part (Joint...
Refers to the quantities related to the 0-order kinematics (joint placements, center of mass position...
void EIGENPY_DLLAPI exposeAngleAxis()