module.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
7 #include "pinocchio/multibody/fwd.hpp"
8 #include "pinocchio/utils/version.hpp"
13 
16 
17 #include <eigenpy/eigenpy.hpp>
18 
19 #include <Eigen/Geometry>
20 #include <eigenpy/geometry.hpp>
21 
22 namespace bp = boost::python;
23 using namespace pinocchio::python;
24 
26 {
27  bp::docstring_options module_docstring_options(true,true,false);
28 
29  bp::scope().attr("__version__") = pinocchio::printVersion();
30  bp::scope().attr("__raw_version__") = bp::str(PINOCCHIO_VERSION);
32 
33  // Enable warnings
34  bp::import("warnings");
35 
36  if(! register_symbolic_link_to_registered_type<Eigen::Quaterniond>())
38  if(! register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
40 
42 
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;
47 
48  eigenpy::enableEigenPySpecific<Matrix6d>();
49  eigenpy::enableEigenPySpecific<Vector6d>();
50  eigenpy::enableEigenPySpecific<Matrix6x>();
51  eigenpy::enableEigenPySpecific<Matrix3x>();
52 
53  exposeSE3();
54  exposeForce();
55  exposeMotion();
56  exposeInertia();
57  exposeJoints();
58  exposeExplog();
59  exposeRpy();
60  exposeSkew();
62 
63  bp::enum_< ::pinocchio::ReferenceFrame >("ReferenceFrame")
64  .value("WORLD",::pinocchio::WORLD)
65  .value("LOCAL",::pinocchio::LOCAL)
66  .value("LOCAL_WORLD_ALIGNED",::pinocchio::LOCAL_WORLD_ALIGNED)
67  .export_values()
68  ;
69 
70  bp::enum_< ::pinocchio::KinematicLevel >("KinematicLevel")
71  .value("POSITION",::pinocchio::POSITION)
72  .value("VELOCITY",::pinocchio::VELOCITY)
73  .value("ACCELERATION",::pinocchio::ACCELERATION)
74  .export_values()
75  ;
76 
77  bp::enum_< ::pinocchio::ArgumentPosition>("ArgumentPosition")
78  .value("ARG0",::pinocchio::ARG0)
79  .value("ARG1",::pinocchio::ARG1)
80  .value("ARG2",::pinocchio::ARG2)
81  .value("ARG3",::pinocchio::ARG3)
82  .value("ARG4",::pinocchio::ARG4)
83  .export_values()
84  ;
85 
86  exposeModel();
87  exposeFrame();
88  exposeData();
90 
92  exposeParsers();
94 
95 #ifdef PINOCCHIO_PYTHON_INTERFACE_WITH_HPP_FCL_PYTHON_BINDINGS
96  exposeFCL();
97 #endif // PINOCCHIO_PYTHON_INTERFACE_WITH_HPP_FCL_PYTHON_BINDINGS
98 
99 #ifdef PINOCCHIO_PYTHON_INTERFACE_WITH_OPENMP
100  exposePool();
102 #endif
103 
104  exposeVersion();
107 
108 }
109 
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.).
Register the conversion from a Python list to a std::vector.
Definition: std-vector.hpp:91
void EIGENPY_DLLAPI enableEigenPy()
BOOST_PYTHON_MODULE(pinocchio_pywrap)
Definition: module.cpp:25
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
Definition: joint-mimic.cpp:15
Refers to the quantities related to the 1st-order kinematics (joint velocities, center of mass veloci...
The LOCAL_WORLD_ALIGNED frame convention corresponds to the frame centered on the moving part (Joint...
int value
Refers to the quantities related to the 0-order kinematics (joint placements, center of mass position...
void exposeConversions()
Definition: conversions.cpp:59
void EIGENPY_DLLAPI exposeAngleAxis()


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:04