From 6c609e48f3e580fd0b96dc2072049e44dd27830c Mon Sep 17 00:00:00 2001 From: Mansard <nmansard@laas.fr> Date: Mon, 29 Sep 2014 10:42:03 +0200 Subject: [PATCH] Bindings completed (some additional bindings could be added for the Joints). Warning remaining at compilation of CRBA. Timings: nq = 36 RNEA = 4.79756 us CRBA = 5.50824 us Cholesky = 2.40469 us Jacobian = 3.68493 us COM+Jcom = 4.024 us --- CMakeLists.txt | 1 + python/test_model.py | 11 ++++++ src/multibody/model.hpp | 4 +- src/python/data.hpp | 67 ++++++++++++++++++++++++++++++---- src/python/eigen_container.hpp | 16 ++++++-- src/python/module.cpp | 1 + src/python/python.cpp | 6 ++- src/python/python.hpp | 1 + src/python/utils.py | 2 + src/spatial/force.hpp | 16 +++++--- src/spatial/motion.hpp | 6 ++- src/spatial/se3.hpp | 4 +- 12 files changed, 114 insertions(+), 21 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 2dce72f8b..704c6ce8c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -76,6 +76,7 @@ SET(HEADERS python/inertia.hpp python/model.hpp python/data.hpp + python/algorithms.hpp ) MAKE_DIRECTORY("${${PROJECT_NAME}_BINARY_DIR}/include/pinocchio") diff --git a/python/test_model.py b/python/test_model.py index 1f750db01..493e5c91c 100644 --- a/python/test_model.py +++ b/python/test_model.py @@ -19,3 +19,14 @@ assert( isapprox(model.gravity.np,np.matrix('0; 0; -9.81; 0; 0; 0')) ) data = model.createData() + +q = zero(model.nq) +qdot = zero(model.nv) +qddot = zero(model.nv) +for i in range(model.nbody): data.a[i] = se3.Motion.Zero() + +se3.rnea(model,data,q,qdot,qddot) +for i in range(model.nbody): + assert( isapprox(data.v[i].np,zero(6)) ) +assert( isapprox(data.a[0].np,-model.gravity.np) ) +assert( isapprox(data.f[-1],model.inertias[-1]*data.a[-1]) ) diff --git a/src/multibody/model.hpp b/src/multibody/model.hpp index 5196c4f8e..cc094f498 100644 --- a/src/multibody/model.hpp +++ b/src/multibody/model.hpp @@ -65,7 +65,10 @@ namespace se3 class Data { public: + typedef Eigen::Matrix<double,6,Eigen::Dynamic> Matrix6x; + typedef Eigen::Matrix<double,3,Eigen::Dynamic> Matrix3x; + public: const Model& model; JointDataVector joints; std::vector<Motion> a; // Body acceleration @@ -78,7 +81,6 @@ namespace se3 std::vector<Inertia> Ycrb; // Inertia of the sub-tree composit rigid body Eigen::MatrixXd M; // Joint Inertia - typedef Eigen::Matrix<double,6,Eigen::Dynamic> Matrix6x; std::vector<Matrix6x> Fcrb; // Spatial forces set, used in CRBA std::vector<Model::Index> lastChild; // Index of the last child (for CRBA) diff --git a/src/python/data.hpp b/src/python/data.hpp index a8e78a202..b287917e4 100644 --- a/src/python/data.hpp +++ b/src/python/data.hpp @@ -18,6 +18,8 @@ namespace se3 struct DataPythonVisitor : public boost::python::def_visitor< DataPythonVisitor > { + typedef Data::Matrix6x Matrix6x; + typedef Data::Matrix3x Matrix3x; public: @@ -27,31 +29,80 @@ namespace se3 return boost::python::incref(boost::python::object(DataHandler(ptr)).ptr()); } +#define ADD_DATA_PROPERTY(TYPE,NAME,DOC) \ + add_property(#NAME, \ + bp::make_function(&DataPythonVisitor::NAME, \ + bp::return_internal_reference<>()), \ + DOC) + //add_property(#NAME,&DataPythonVisitor::NAME,DOC) + //bp::make_function(&ModelPythonVisitor::inertias, + // bp::return_internal_reference<>()) ) +#define IMPL_DATA_PROPERTY(TYPE,NAME,DOC) \ + static TYPE & NAME( DataHandler & d ) { return d->NAME; } + + /* --- Exposing C++ API to python through the handler ----------------- */ template<class PyClass> void visit(PyClass& cl) const { cl + .ADD_DATA_PROPERTY(std::vector<Motion>,a,"Body acceleration") + .ADD_DATA_PROPERTY(std::vector<Motion>,v,"Body velocity") + .ADD_DATA_PROPERTY(std::vector<Force>,f,"Body force") + .ADD_DATA_PROPERTY(std::vector<SE3>,oMi,"Body absolute placement (wrt world)") + .ADD_DATA_PROPERTY(std::vector<SE3>,liMi,"Body relative placement (wrt parent)") + .ADD_DATA_PROPERTY(Eigen::VectorXd,tau,"Joint forces") + .ADD_DATA_PROPERTY(std::vector<Inertia>,Ycrb,"Inertia of the sub-tree composit rigid body") + .ADD_DATA_PROPERTY(Eigen::MatrixXd,M,"Joint Inertia") + .ADD_DATA_PROPERTY(std::vector<Matrix6x>,Fcrb,"Spatial forces set, used in CRBA") + .ADD_DATA_PROPERTY(std::vector<Model::Index>,lastChild,"Index of the last child (for CRBA)") + .ADD_DATA_PROPERTY(std::vector<int>,nvSubtree,"Dimension of the subtree motion space (for CRBA)") + .ADD_DATA_PROPERTY(Eigen::MatrixXd,U,"Joint Inertia square root (upper triangle)") + .ADD_DATA_PROPERTY(Eigen::VectorXd,D,"Diagonal of UDUT inertia decomposition") + .ADD_DATA_PROPERTY(std::vector<int>,parents_fromRow,"First previous non-zero row in M (used in Cholesky)") + .ADD_DATA_PROPERTY(std::vector<int>,nvSubtree_fromRow,"") + .ADD_DATA_PROPERTY(Eigen::MatrixXd,J,"Jacobian of joint placement") + .ADD_DATA_PROPERTY(std::vector<SE3>,iMf,"Body placement wrt to algorithm end effector.") + .ADD_DATA_PROPERTY(std::vector<Eigen::Vector3d>,com,"Subtree com position.") + .ADD_DATA_PROPERTY(std::vector<double>,mass,"Subtree total mass.") + .ADD_DATA_PROPERTY(Matrix3x,Jcom,"Jacobian of center of mass.") ; } - - /* --- Expose --------------------------------------------------------- */ - static void expose() + IMPL_DATA_PROPERTY(std::vector<Motion>,a,"Body acceleration") + IMPL_DATA_PROPERTY(std::vector<Motion>,v,"Body velocity") + IMPL_DATA_PROPERTY(std::vector<Force>,f,"Body force") + IMPL_DATA_PROPERTY(std::vector<SE3>,oMi,"Body absolute placement (wrt world)") + IMPL_DATA_PROPERTY(std::vector<SE3>,liMi,"Body relative placement (wrt parent)") + IMPL_DATA_PROPERTY(Eigen::VectorXd,tau,"Joint forces") + IMPL_DATA_PROPERTY(std::vector<Inertia>,Ycrb,"Inertia of the sub-tree composit rigid body") + IMPL_DATA_PROPERTY(Eigen::MatrixXd,M,"Joint Inertia") + IMPL_DATA_PROPERTY(std::vector<Matrix6x>,Fcrb,"Spatial forces set, used in CRBA") + IMPL_DATA_PROPERTY(std::vector<Model::Index>,lastChild,"Index of the last child (for CRBA)") + IMPL_DATA_PROPERTY(std::vector<int>,nvSubtree,"Dimension of the subtree motion space (for CRBA)") + IMPL_DATA_PROPERTY(Eigen::MatrixXd,U,"Joint Inertia square root (upper triangle)") + IMPL_DATA_PROPERTY(Eigen::VectorXd,D,"Diagonal of UDUT inertia decomposition") + IMPL_DATA_PROPERTY(std::vector<int>,parents_fromRow,"First previous non-zero row in M (used in Cholesky)") + IMPL_DATA_PROPERTY(std::vector<int>,nvSubtree_fromRow,"") + IMPL_DATA_PROPERTY(Eigen::MatrixXd,J,"Jacobian of joint placement") + IMPL_DATA_PROPERTY(std::vector<SE3>,iMf,"Body placement wrt to algorithm end effector.") + IMPL_DATA_PROPERTY(std::vector<Eigen::Vector3d>,com,"Subtree com position.") + IMPL_DATA_PROPERTY(std::vector<double>,mass,"Subtree total mass.") + IMPL_DATA_PROPERTY(Matrix3x,Jcom,"Jacobian of center of mass.") + + /* --- Expose --------------------------------------------------------- */ + static void expose() { bp::class_<DataHandler>("Data", - "Articulated rigid body data (const)", - bp::no_init) + "Articulated rigid body data (const)", + bp::no_init) .def(DataPythonVisitor()); bp::to_python_converter< DataHandler::SmartPtr_t,DataPythonVisitor >(); } - }; - - }} // namespace se3::python #endif // ifndef __se3_python_data_hpp__ diff --git a/src/python/eigen_container.hpp b/src/python/eigen_container.hpp index 296d2c3bb..39948bdcd 100644 --- a/src/python/eigen_container.hpp +++ b/src/python/eigen_container.hpp @@ -35,12 +35,22 @@ namespace se3 } static EigenObject getItem( const stdVectorAligned & Ys,int i) - { return Ys[i]; } + { + assert( Ys.size()<INT_MAX ); + if( i<0 ) i = int(Ys.size())+i; + assert( (i>=0) && (i<int(Ys.size())) ); + return Ys[i]; + } static void setItem( stdVectorAligned & Ys, int i,const EigenObject_fx & Y) - { Ys[i] = Y; } - static int length( const stdVectorAligned & Ys ) + { + assert( Ys.size()<INT_MAX ); + if( i<0 ) i = int(Ys.size())+i; + assert( (i>=0) && (i<int(Ys.size())) ); + Ys[i] = Y; + } + static typename stdVectorAligned::size_type length( const stdVectorAligned & Ys ) { return Ys.size(); } static void expose(const std::string & className) diff --git a/src/python/module.cpp b/src/python/module.cpp index b621f2a60..690ba9c0f 100644 --- a/src/python/module.cpp +++ b/src/python/module.cpp @@ -24,5 +24,6 @@ BOOST_PYTHON_MODULE(libpinocchio_pywrap) se3::python::exposeInertia(); se3::python::exposeModel(); + se3::python::exposeAlgorithms(); } diff --git a/src/python/python.cpp b/src/python/python.cpp index 8545b6171..8554689a5 100644 --- a/src/python/python.cpp +++ b/src/python/python.cpp @@ -6,6 +6,7 @@ #include "pinocchio/python/model.hpp" #include "pinocchio/python/data.hpp" +#include "pinocchio/python/algorithms.hpp" namespace se3 { @@ -36,5 +37,8 @@ namespace se3 ModelPythonVisitor::expose(); DataPythonVisitor::expose(); } - + void exposeAlgorithms() + { + AlgorithmsPythonVisitor::expose(); + } }} // namespace se3::python diff --git a/src/python/python.hpp b/src/python/python.hpp index dc00aa812..f79d68dce 100644 --- a/src/python/python.hpp +++ b/src/python/python.hpp @@ -11,6 +11,7 @@ namespace se3 void exposeInertia(); void exposeModel(); + void exposeAlgorithms(); }} // namespace se3::python diff --git a/src/python/utils.py b/src/python/utils.py index 0b2152f0e..8f41245a2 100644 --- a/src/python/utils.py +++ b/src/python/utils.py @@ -10,6 +10,8 @@ def skew(p): return np.matrix([ [ 0,-z,y ], [ z,0,-x ], [ -y,x,0 ] ],np.double) def isapprox(a,b,epsilon=1e-6): + if "np" in a.__class__.__dict__: a = a.np + if "np" in b.__class__.__dict__: b = b.np if issubclass(a.__class__,np.ndarray) and issubclass(b.__class__,np.ndarray): return np.allclose(a,b,epsilon) else: diff --git a/src/spatial/force.hpp b/src/spatial/force.hpp index aa021e0cd..c119f8018 100644 --- a/src/spatial/force.hpp +++ b/src/spatial/force.hpp @@ -24,13 +24,17 @@ namespace se3 public: // Constructors ForceTpl() : m_n(), m_f() {} - template<typename f_t,typename n_t> - ForceTpl(const Eigen::MatrixBase<f_t> & f,const Eigen::MatrixBase<n_t> & n) + template<typename f3_t,typename n3_t> + ForceTpl(const Eigen::MatrixBase<f3_t> & f,const Eigen::MatrixBase<n3_t> & n) : m_n(n), m_f(f) {} - template<typename f_t> - ForceTpl(const Eigen::MatrixBase<f_t> & v) - : m_n(v.template segment<3>(ANGULAR)), - m_f(v.template segment<3>(LINEAR)) {} + template<typename f6> + ForceTpl(const Eigen::MatrixBase<f6> & f) + : m_n(f.template segment<3>(ANGULAR)), + m_f(f.template segment<3>(LINEAR)) + { + EIGEN_STATIC_ASSERT_VECTOR_ONLY(f6); + assert( f.size() == 6 ); + } template<typename S2,int O2> ForceTpl(const ForceTpl<S2,O2> & clone) : m_n(clone.angular()), m_f(clone.linear()) {} diff --git a/src/spatial/motion.hpp b/src/spatial/motion.hpp index 3e2d02a5c..ac6d763fd 100644 --- a/src/spatial/motion.hpp +++ b/src/spatial/motion.hpp @@ -31,7 +31,11 @@ namespace se3 template<typename v6> MotionTpl(const Eigen::MatrixBase<v6> & v) : m_w(v.template segment<3>(ANGULAR)), - m_v(v.template segment<3>(LINEAR)) {} + m_v(v.template segment<3>(LINEAR)) + { + EIGEN_STATIC_ASSERT_VECTOR_ONLY(v6); + assert( v.size() == 6 ); + } template<typename S2,int O2> MotionTpl(const MotionTpl<S2,O2> & clone) : m_w(clone.angular()),m_v(clone.linear()) {} diff --git a/src/spatial/se3.hpp b/src/spatial/se3.hpp index 13915199d..74184364b 100644 --- a/src/spatial/se3.hpp +++ b/src/spatial/se3.hpp @@ -8,6 +8,7 @@ namespace se3 { + /* Type returned by the "se3Action" and "se3ActionInverse" functions. */ namespace internal { template<typename D> @@ -130,7 +131,8 @@ namespace se3 operator Matrix4() const { return toHomogeneousMatrix(); } operator Matrix6() const { return toActionMatrix(); } SE3Tpl operator*(const SE3Tpl & m2) const { return this->act(m2); } - friend std::ostream & operator << (std::ostream & os,const SE3Tpl & X) { X.disp(os); return os; } + friend std::ostream & operator << (std::ostream & os,const SE3Tpl & X) + { X.disp(os); return os; } public: private: -- GitLab