From c81cc2dc887e8e4fa046c45c863a8e4a49a1ee4f Mon Sep 17 00:00:00 2001 From: Mansard <nmansard@laas.fr> Date: Wed, 12 Nov 2014 19:01:37 +0100 Subject: [PATCH] Python: corrected a bug in data bindings with Eigen members. --- src/python/data.hpp | 50 ++++++++++++++++++++++++--------------------- 1 file changed, 27 insertions(+), 23 deletions(-) diff --git a/src/python/data.hpp b/src/python/data.hpp index b287917e4..d9aacaf49 100644 --- a/src/python/data.hpp +++ b/src/python/data.hpp @@ -34,12 +34,16 @@ namespace se3 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 ADD_DATA_PROPERTY_CONST(TYPE,NAME,DOC) \ + add_property(#NAME, \ + bp::make_function(&DataPythonVisitor::NAME), \ + DOC) + #define IMPL_DATA_PROPERTY(TYPE,NAME,DOC) \ static TYPE & NAME( DataHandler & d ) { return d->NAME; } - +#define IMPL_DATA_PROPERTY_CONST(TYPE,NAME,DOC) \ + static TYPE NAME( DataHandler & d ) { return d->NAME; } + /* --- Exposing C++ API to python through the handler ----------------- */ template<class PyClass> @@ -51,21 +55,21 @@ namespace se3 .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_CONST(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_CONST(Eigen::MatrixXd,M,"Joint Inertia") + .ADD_DATA_PROPERTY_CONST(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_CONST(Eigen::MatrixXd,U,"Joint Inertia square root (upper triangle)") + .ADD_DATA_PROPERTY_CONST(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_CONST(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_CONST(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.") + .ADD_DATA_PROPERTY_CONST(Matrix3x,Jcom,"Jacobian of center of mass.") ; } @@ -74,24 +78,24 @@ namespace se3 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_CONST(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_CONST(Eigen::MatrixXd,M,"Joint Inertia") + IMPL_DATA_PROPERTY_CONST(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_CONST(Eigen::MatrixXd,U,"Joint Inertia square root (upper triangle)") + IMPL_DATA_PROPERTY_CONST(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_CONST(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_CONST(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() + IMPL_DATA_PROPERTY_CONST(Matrix3x,Jcom,"Jacobian of center of mass.") + + /* --- Expose --------------------------------------------------------- */ + static void expose() { bp::class_<DataHandler>("Data", "Articulated rigid body data (const)", -- GitLab