From cb989968843c54c59e0c86d1aa38fa0f55c3f542 Mon Sep 17 00:00:00 2001 From: jcarpent <jcarpent@laas.fr> Date: Mon, 1 Aug 2016 14:58:27 +0200 Subject: [PATCH] [Python] Split bindings in several .o files --- bindings/python/CMakeLists.txt | 46 +- bindings/python/algorithm/algorithms.hpp | 58 ++ bindings/python/algorithm/expose-aba.cpp | 48 ++ .../python/algorithm/expose-algorithms.cpp | 45 ++ bindings/python/algorithm/expose-cat.cpp | 46 ++ bindings/python/algorithm/expose-com.cpp | 102 +++ bindings/python/algorithm/expose-crba.cpp | 61 ++ bindings/python/algorithm/expose-dynamics.cpp | 73 +++ bindings/python/algorithm/expose-energy.cpp | 63 ++ bindings/python/algorithm/expose-frames.cpp | 74 +++ bindings/python/algorithm/expose-geometry.cpp | 105 ++++ bindings/python/algorithm/expose-jacobian.cpp | 72 +++ bindings/python/algorithm/expose-joints.cpp | 94 +++ .../python/algorithm/expose-kinematics.cpp | 77 +++ bindings/python/algorithm/expose-rnea.cpp | 60 ++ bindings/python/algorithms.hpp | 579 ------------------ bindings/python/data.hpp | 7 +- bindings/python/explog.hpp | 4 +- bindings/python/expose-SE3.cpp | 34 + bindings/python/expose-data.cpp | 32 + bindings/python/expose-explog.cpp | 33 + bindings/python/expose-force.cpp | 34 + bindings/python/expose-frame.cpp | 32 + bindings/python/expose-geometry.cpp | 37 ++ bindings/python/expose-inertia.cpp | 34 + bindings/python/expose-joints.cpp | 45 ++ bindings/python/expose-model.cpp | 32 + bindings/python/expose-motion.cpp | 34 + bindings/python/expose-parsers.cpp | 32 + bindings/python/frame.hpp | 3 +- bindings/python/geometry-data.hpp | 10 +- bindings/python/geometry-model.hpp | 76 ++- bindings/python/geometry-object.hpp | 4 +- bindings/python/joint.hpp | 2 - bindings/python/joints-models.hpp | 2 - bindings/python/joints-variant.hpp | 10 +- bindings/python/model.hpp | 10 +- bindings/python/module.cpp | 6 +- bindings/python/parsers.hpp | 11 +- bindings/python/python.cpp | 92 --- bindings/python/python.hpp | 22 +- 41 files changed, 1484 insertions(+), 757 deletions(-) create mode 100644 bindings/python/algorithm/algorithms.hpp create mode 100644 bindings/python/algorithm/expose-aba.cpp create mode 100644 bindings/python/algorithm/expose-algorithms.cpp create mode 100644 bindings/python/algorithm/expose-cat.cpp create mode 100644 bindings/python/algorithm/expose-com.cpp create mode 100644 bindings/python/algorithm/expose-crba.cpp create mode 100644 bindings/python/algorithm/expose-dynamics.cpp create mode 100644 bindings/python/algorithm/expose-energy.cpp create mode 100644 bindings/python/algorithm/expose-frames.cpp create mode 100644 bindings/python/algorithm/expose-geometry.cpp create mode 100644 bindings/python/algorithm/expose-jacobian.cpp create mode 100644 bindings/python/algorithm/expose-joints.cpp create mode 100644 bindings/python/algorithm/expose-kinematics.cpp create mode 100644 bindings/python/algorithm/expose-rnea.cpp delete mode 100644 bindings/python/algorithms.hpp create mode 100644 bindings/python/expose-SE3.cpp create mode 100644 bindings/python/expose-data.cpp create mode 100644 bindings/python/expose-explog.cpp create mode 100644 bindings/python/expose-force.cpp create mode 100644 bindings/python/expose-frame.cpp create mode 100644 bindings/python/expose-geometry.cpp create mode 100644 bindings/python/expose-inertia.cpp create mode 100644 bindings/python/expose-joints.cpp create mode 100644 bindings/python/expose-model.cpp create mode 100644 bindings/python/expose-motion.cpp create mode 100644 bindings/python/expose-parsers.cpp delete mode 100644 bindings/python/python.cpp diff --git a/bindings/python/CMakeLists.txt b/bindings/python/CMakeLists.txt index 05f928c5a..e0feeef3e 100644 --- a/bindings/python/CMakeLists.txt +++ b/bindings/python/CMakeLists.txt @@ -36,7 +36,7 @@ MACRO(ADD_SOURCE_GROUP FILENAMES) ENDMACRO(ADD_SOURCE_GROUP FILENAMES) IF(BUILD_PYTHON_INTERFACE) - # --- Collect header files + SET(${PROJECT_NAME}_PYTHON_HEADERS eigen_container.hpp handler.hpp @@ -52,7 +52,7 @@ IF(BUILD_PYTHON_INTERFACE) frame.hpp model.hpp data.hpp - algorithms.hpp + algorithm/algorithms.hpp parsers.hpp explog.hpp geometry-object.hpp @@ -60,10 +60,48 @@ IF(BUILD_PYTHON_INTERFACE) geometry-data.hpp ) + SET(${PROJECT_NAME}_PYTHON_SOURCES + module.cpp + expose-SE3.cpp + expose-motion.cpp + expose-force.cpp + expose-inertia.cpp + expose-explog.cpp + expose-joints.cpp + expose-frame.cpp + expose-model.cpp + expose-data.cpp + expose-parsers.cpp + algorithm/expose-algorithms.cpp + algorithm/expose-com.cpp + algorithm/expose-kinematics.cpp + algorithm/expose-dynamics.cpp + algorithm/expose-crba.cpp + algorithm/expose-rnea.cpp + algorithm/expose-aba.cpp + algorithm/expose-jacobian.cpp + algorithm/expose-joints.cpp + algorithm/expose-energy.cpp + algorithm/expose-frames.cpp + algorithm/expose-cat.cpp + ) + + LIST(APPEND ${PROJECT_NAME}_PYTHON_HEADERS + geometry-object.hpp + geometry-model.hpp + geometry-data.hpp + ) + + LIST(APPEND ${PROJECT_NAME}_PYTHON_SOURCES + expose-geometry.cpp + algorithm/expose-geometry.cpp + ) + LIST(APPEND HEADERS ${${PROJECT_NAME}_PYTHON_HEADERS}) LIST(REMOVE_DUPLICATES HEADERS) MAKE_DIRECTORY("${${PROJECT_NAME}_BINARY_DIR}/include/pinocchio/bindings/python") + MAKE_DIRECTORY("${${PROJECT_NAME}_BINARY_DIR}/include/pinocchio/bindings/python/algorithm") FOREACH(header ${${PROJECT_NAME}_PYTHON_HEADERS}) GET_FILENAME_COMPONENT(headerName ${header} NAME) GET_FILENAME_COMPONENT(headerPath ${header} PATH) @@ -79,7 +117,9 @@ IF(BUILD_PYTHON_INTERFACE) # --- COMPILE WRAPPER SET(PYWRAP ${PROJECT_NAME}_pywrap) - ADD_LIBRARY(${PYWRAP} SHARED module.cpp python.cpp) + ADD_LIBRARY(${PYWRAP} SHARED ${${PROJECT_NAME}_PYTHON_SOURCES} ${${PROJECT_NAME}_PYTHON_HEADERS}) + ADD_HEADER_GROUP(${PROJECT_NAME}_PYTHON_HEADERS) + ADD_SOURCE_GROUP(${PROJECT_NAME}_PYTHON_SOURCES) PKG_CONFIG_USE_DEPENDENCY(${PYWRAP} eigenpy) IF(URDFDOM_FOUND) diff --git a/bindings/python/algorithm/algorithms.hpp b/bindings/python/algorithm/algorithms.hpp new file mode 100644 index 000000000..ac5d26b6e --- /dev/null +++ b/bindings/python/algorithm/algorithms.hpp @@ -0,0 +1,58 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#ifndef __se3_python_algorithm_hpp__ +#define __se3_python_algorithm_hpp__ + +#include <eigenpy/exception.hpp> +#include <eigenpy/eigenpy.hpp> + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/model.hpp" +#include "pinocchio/bindings/python/data.hpp" + +namespace se3 +{ + namespace python + { + + typedef eigenpy::UnalignedEquivalent<Eigen::VectorXd>::type VectorXd_fx; + typedef eigenpy::UnalignedEquivalent<Eigen::MatrixXd>::type MatrixXd_fx; + + void exposeJointsAlgo(); + void exposeABA(); + void exposeCRBA(); + void exposeRNEA(); + void exposeCOM(); + void exposeFramesAlgo(); + void exposeEnergy(); + void exposeKinematics(); + void exposeDynamics(); + void exposeCAT(); + void exposeJacobian(); + +#ifdef WITH_HPP_FCL + void exposeGeometryAlgo(); +#endif // ifdef WITH_HPP_FCL + + void exposeAlgorithms(); + + } // namespace python +} // namespace se3 + +#endif // ifndef __se3_python_algorithm_hpp__ + diff --git a/bindings/python/algorithm/expose-aba.cpp b/bindings/python/algorithm/expose-aba.cpp new file mode 100644 index 000000000..5e4ab5c2c --- /dev/null +++ b/bindings/python/algorithm/expose-aba.cpp @@ -0,0 +1,48 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/aba.hpp" + +namespace se3 +{ + namespace python + { + + static Eigen::MatrixXd aba_proxy(const ModelHandler & model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & v, + const VectorXd_fx & tau) + { + aba(*model,*data,q,v,tau); + return data->ddq; + } + + void exposeABA() + { + bp::def("aba",aba_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)", + "Joint velocity v (size Model::nv)", + "Joint torque tau (size Model::nv)"), + "Compute ABA, put the result in Data::ddq and return it."); + + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-algorithms.cpp b/bindings/python/algorithm/expose-algorithms.cpp new file mode 100644 index 000000000..8180a398c --- /dev/null +++ b/bindings/python/algorithm/expose-algorithms.cpp @@ -0,0 +1,45 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" + +namespace se3 +{ + namespace python + { + + void exposeAlgorithms() + { + exposeJointsAlgo(); + exposeABA(); + exposeCRBA(); + exposeRNEA(); + exposeCOM(); + exposeFramesAlgo(); + exposeEnergy(); + exposeKinematics(); + exposeDynamics(); + exposeCAT(); + exposeJacobian(); + +#ifdef WITH_HPP_FCL + exposeGeometryAlgo(); +#endif // ifdef WITH_HPP_FCL + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-cat.cpp b/bindings/python/algorithm/expose-cat.cpp new file mode 100644 index 000000000..15c0614d8 --- /dev/null +++ b/bindings/python/algorithm/expose-cat.cpp @@ -0,0 +1,46 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/compute-all-terms.hpp" + +namespace se3 +{ + namespace python + { + static void computeAllTerms_proxy(const ModelHandler & model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & v) + { + data->M.fill(0); + computeAllTerms(*model,*data,q,v); + data->M.triangularView<Eigen::StrictlyLower>() + = data->M.transpose().triangularView<Eigen::StrictlyLower>(); + } + + void exposeCAT() + { + bp::def("computeAllTerms",computeAllTerms_proxy, + bp::args("Model","Data", + "Configuration q (size Model::nq)", + "Velocity v (size Model::nv)"), + "Compute all the terms M, non linear effects and Jacobians in" + "in the same loop and put the results in data."); + } + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-com.cpp b/bindings/python/algorithm/expose-com.cpp new file mode 100644 index 000000000..2e2ad586f --- /dev/null +++ b/bindings/python/algorithm/expose-com.cpp @@ -0,0 +1,102 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/center-of-mass.hpp" + +namespace se3 +{ + namespace python + { + + static SE3::Vector3 + com_0_proxy(const ModelHandler& model, + DataHandler & data, + const VectorXd_fx & q, + const bool updateKinematics = true) + { + return centerOfMass(*model,*data,q, + true, + updateKinematics); + } + + static SE3::Vector3 + com_1_proxy(const ModelHandler& model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & v, + const bool updateKinematics = true) + { + return centerOfMass(*model,*data,q,v, + true, + updateKinematics); + } + + static SE3::Vector3 + com_2_proxy(const ModelHandler & model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & v, + const VectorXd_fx & a, + const bool updateKinematics = true) + { + return centerOfMass(*model,*data,q,v,a, + true, + updateKinematics); + } + + static Data::Matrix3x + Jcom_proxy(const ModelHandler& model, + DataHandler & data, + const VectorXd_fx & q) + { + return jacobianCenterOfMass(*model,*data,q); + } + + void exposeCOM() + { + bp::def("centerOfMass",com_0_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)", + "Update kinematics"), + "Compute the center of mass, putting the result in Data and return it."); + + bp::def("centerOfMass",com_1_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)", + "Joint velocity v (size Model::nv)", + "Update kinematics"), + "Computes the center of mass position and velocuty by storing the result in Data" + "and returns the center of mass position of the full model expressed in the world frame."); + + bp::def("centerOfMass",com_2_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)", + "Joint velocity v (size Model::nv)", + "Joint acceleration a (size Model::nv)", + "Update kinematics"), + "Computes the center of mass position, velocity and acceleration by storing the result in Data" + "and returns the center of mass position of the full model expressed in the world frame."); + + bp::def("jacobianCenterOfMass",Jcom_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)"), + "Computes the jacobian of the center of mass, puts the result in Data and return it."); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-crba.cpp b/bindings/python/algorithm/expose-crba.cpp new file mode 100644 index 000000000..5c4405d35 --- /dev/null +++ b/bindings/python/algorithm/expose-crba.cpp @@ -0,0 +1,61 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/crba.hpp" + +namespace se3 +{ + namespace python + { + static Eigen::MatrixXd crba_proxy(const ModelHandler& model, + DataHandler & data, + const VectorXd_fx & q) + { + data->M.fill(0); + crba(*model,*data,q); + data->M.triangularView<Eigen::StrictlyLower>() + = data->M.transpose().triangularView<Eigen::StrictlyLower>(); + return data->M; + } + + static Data::Matrix6x ccrba_proxy(const ModelHandler& model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & v) + { + ccrba(*model,*data,q,v); + return data->Ag; + } + + void exposeCRBA() + { + bp::def("crba",crba_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)"), + "Computes CRBA, put the result in Data and return it."); + + bp::def("ccrba",ccrba_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)", + "Joint velocity v (size Model::nv)"), + "Computes the centroidal mapping, the centroidal momentum and the Centroidal Composite Rigid Body Inertia, puts the result in Data and returns the centroidal mapping."); + + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-dynamics.cpp b/bindings/python/algorithm/expose-dynamics.cpp new file mode 100644 index 000000000..5624fe179 --- /dev/null +++ b/bindings/python/algorithm/expose-dynamics.cpp @@ -0,0 +1,73 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/dynamics.hpp" + +namespace se3 +{ + namespace python + { + static Eigen::MatrixXd fd_llt_proxy(const ModelHandler & model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & v, + const VectorXd_fx & tau, + const eigenpy::MatrixXd_fx & J, + const VectorXd_fx & gamma, + const bool update_kinematics = true) + { + forwardDynamics(*model,*data,q,v,tau,J,gamma,update_kinematics); + return data->ddq; + } + + static Eigen::MatrixXd id_llt_proxy(const ModelHandler & model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & v_before, + const eigenpy::MatrixXd_fx & J, + const double r_coeff, + const bool update_kinematics = true) + { + impulseDynamics(*model,*data,q,v_before,J,r_coeff,update_kinematics); + return data->dq_after; + } + + void exposeDynamics() + { + bp::def("forwardDynamics",fd_llt_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)", + "Joint velocity v (size Model::nv)", + "Joint torque tau (size Model::nv)", + "Contact Jacobian J (size nb_constraint * Model::nv)", + "Contact drift gamma (size nb_constraint)", + "Update kinematics (if true, it updates the dynamic variable according to the current state)"), + "Solves the forward dynamics problem with contacts, puts the result in Data::ddq and return it. The contact forces are stored in data.lambda_c"); + + bp::def("impactDynamics",id_llt_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)", + "Joint velocity before impact v_before (size Model::nv)", + "Contact Jacobian J (size nb_constraint * Model::nv)", + "Coefficient of restitution r_coeff (0 = rigid impact; 1 = fully elastic impact.", + "Update kinematics (if true, it updates only the joint space inertia matrix)"), + "Solve the impact dynamics problem with contacts, put the result in Data::dq_after and return it. The contact impulses are stored in data.impulse_c"); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-energy.cpp b/bindings/python/algorithm/expose-energy.cpp new file mode 100644 index 000000000..3864556f5 --- /dev/null +++ b/bindings/python/algorithm/expose-energy.cpp @@ -0,0 +1,63 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/energy.hpp" + +namespace se3 +{ + namespace python + { + static double kineticEnergy_proxy(const ModelHandler & model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & v, + const bool update_kinematics = true) + { + return kineticEnergy(*model,*data,q,v,update_kinematics); + } + + static double potentialEnergy_proxy(const ModelHandler & model, + DataHandler & data, + const VectorXd_fx & q, + const bool update_kinematics = true) + { + return potentialEnergy(*model,*data,q,update_kinematics); + } + + void exposeEnergy() + { + bp::def("kineticEnergy",kineticEnergy_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)", + "Joint velocity v (size Model::nv)", + "Update kinematics (bool)"), + "Computes the kinematic energy of the model for the " + "given joint configuration and velocity and stores the result " + " in data.kinetic_energy. By default, the kinematics of model is updated."); + + bp::def("potentialEnergy",potentialEnergy_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)", + "Update kinematics (bool)"), + "Computes the potential energy of the model for the " + "given the joint configuration and stores the result " + " in data.potential_energy. By default, the kinematics of model is updated."); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-frames.cpp b/bindings/python/algorithm/expose-frames.cpp new file mode 100644 index 000000000..238d6ca2b --- /dev/null +++ b/bindings/python/algorithm/expose-frames.cpp @@ -0,0 +1,74 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/frames.hpp" + +namespace se3 +{ + namespace python + { + + static Data::Matrix6x frame_jacobian_proxy(const ModelHandler & model, + DataHandler & data, + const VectorXd_fx & q, + Model::FrameIndex frame_id, + bool local, + bool update_geometry + ) + { + Data::Matrix6x J(6,model->nv); J.setZero(); + + if (update_geometry) + computeJacobians( *model,*data,q ); + + if(local) getFrameJacobian<true> (*model, *data, frame_id, J); + else getFrameJacobian<false> (*model, *data, frame_id, J); + + return J; + } + + static void frames_fk_0_proxy(const ModelHandler& model, + DataHandler & data, + const VectorXd_fx & q + ) + { + framesForwardKinematics( *model,*data,q ); + } + + void exposeFramesAlgo() + { + bp::def("framesKinematics",frames_fk_0_proxy, + bp::args("Model","Data", + "Configuration q (size Model::nq)"), + "Compute the placements of all the operational frames " + "and put the results in data."); + + bp::def("frameJacobian",frame_jacobian_proxy, + bp::args("Model","Data", + "Configuration q (size Model::nq)", + "Operational frame ID (int)", + "frame (true = local, false = world)", + "update_geometry (true = recompute the kinematics)"), + "Call computeJacobians if update_geometry is true. If not, user should call computeJacobians first." + "Then call getJacobian and return the resulted jacobian matrix. Attention: if update_geometry is true, the " + "function computes all the jacobians of the model. It is therefore outrageously costly wrt a dedicated " + "call. Use only with update_geometry for prototyping."); + + } + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-geometry.cpp b/bindings/python/algorithm/expose-geometry.cpp new file mode 100644 index 000000000..dadf7c06c --- /dev/null +++ b/bindings/python/algorithm/expose-geometry.cpp @@ -0,0 +1,105 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/geometry.hpp" +#include "pinocchio/bindings/python/geometry-object.hpp" +#include "pinocchio/bindings/python/geometry-model.hpp" +#include "pinocchio/bindings/python/geometry-data.hpp" + +namespace se3 +{ + namespace python + { + + static void updateGeometryPlacements_proxy(const ModelHandler & model, + DataHandler & data, + const GeometryModelHandler & geom_model, + GeometryDataHandler & geom_data, + const VectorXd_fx & q + ) + { + return updateGeometryPlacements(*model, *data, *geom_model, *geom_data, q); + } + +#ifdef WITH_HPP_FCL + static bool computeCollisions_proxy(GeometryDataHandler & data_geom, + const bool stopAtFirstCollision) + { + return computeCollisions(*data_geom, stopAtFirstCollision); + } + + static bool computeGeometryAndCollisions_proxy(const ModelHandler & model, + DataHandler & data, + const GeometryModelHandler & model_geom, + GeometryDataHandler & data_geom, + const VectorXd_fx & q, + const bool stopAtFirstCollision) + { + return computeCollisions(*model,*data,*model_geom, *data_geom, q, stopAtFirstCollision); + } + + static void computeDistances_proxy(GeometryDataHandler & data_geom) + { + computeDistances(*data_geom); + } + + static void computeGeometryAndDistances_proxy(const ModelHandler & model, + DataHandler & data, + const GeometryModelHandler & model_geom, + GeometryDataHandler & data_geom, + const Eigen::VectorXd & q + ) + { + computeDistances(*model, *data, *model_geom, *data_geom, q); + } +#endif // WITH_HPP_FCL + + void exposeGeometryAlgo() + { + bp::def("updateGeometryPlacements",updateGeometryPlacements_proxy, + bp::args("Model", "Data", "GeometryModel", "GeometryData", "Configuration q (size Model::nq)"), + "Update the placement of the collision objects according to the current configuration." + "The algorithm also updates the current placement of the joint in Data." + ); + +#ifdef WITH_HPP_FCL + bp::def("computeCollisions",computeCollisions_proxy, + bp::args("GeometryData","bool"), + "Determine if collision pairs are effectively in collision." + ); + + bp::def("computeGeometryAndCollisions",computeGeometryAndCollisions_proxy, + bp::args("Model","Data","GeometryModel","GeometryData","Configuration q (size Model::nq)", "bool"), + "Update the geometry for a given configuration and" + "determine if all collision pairs are effectively in collision or not." + ); + + bp::def("computeDistances",computeDistances_proxy, + bp::args("GeometryData"), + "Compute the distance between each collision pair." + ); + + bp::def("computeGeometryAndDistances",computeGeometryAndDistances_proxy, + bp::args("Model","Data","GeometryModel","GeometryData","Configuration q (size Model::nq)"), + "Update the geometry for a given configuration and" + "compute the distance between each collision pair" + ); +#endif // WITH_HPP_FCL + } + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-jacobian.cpp b/bindings/python/algorithm/expose-jacobian.cpp new file mode 100644 index 000000000..2aba3b733 --- /dev/null +++ b/bindings/python/algorithm/expose-jacobian.cpp @@ -0,0 +1,72 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/jacobian.hpp" + +namespace se3 +{ + namespace python + { + + static void compute_jacobians_proxy(const ModelHandler& model, + DataHandler & data, + const VectorXd_fx & q) + { + computeJacobians(*model,*data,q); + } + + + static Data::Matrix6x + jacobian_proxy(const ModelHandler & model, + DataHandler & data, + const VectorXd_fx & q, + Model::JointIndex jointId, + bool local, + bool update_geometry) + { + Data::Matrix6x J(6,model->nv); J.setZero(); + + if (update_geometry) + computeJacobians(*model,*data,q); + + if(local) getJacobian<true> (*model,*data,jointId,J); + else getJacobian<false> (*model,*data,jointId,J); + + return J; + } + + void exposeJacobian() + { + bp::def("computeJacobians",compute_jacobians_proxy, + bp::args("Model","Data", + "Joint configuration q (size Model::nq)"), + "Calling computeJacobians"); + + bp::def("jacobian",jacobian_proxy, + bp::args("Model, the model of the kinematic tree", + "Data, the data associated to the model where the results are stored", + "Joint configuration q (size Model::nq)", + "Joint ID, the index of the joint.", + "frame (true = local, false = world)", + "update_geometry (true = update the value of the total jacobian)"), + "Computes the jacobian of a given given joint according to the given input configuration." + "If local is set to true, it returns the jacobian associated to the joint frame. Otherwise, it returns the jacobian of the frame coinciding with the world frame."); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-joints.cpp b/bindings/python/algorithm/expose-joints.cpp new file mode 100644 index 000000000..54023c195 --- /dev/null +++ b/bindings/python/algorithm/expose-joints.cpp @@ -0,0 +1,94 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" + +namespace se3 +{ + namespace python + { + static Eigen::VectorXd integrate_proxy(const ModelHandler & model, + const VectorXd_fx & q, + const VectorXd_fx & v) + { + return integrate(*model,q,v); + } + + static Eigen::VectorXd interpolate_proxy(const ModelHandler & model, + const VectorXd_fx & q1, + const VectorXd_fx & q2, + const double u) + { + return interpolate(*model,q1,q2,u); + } + + static Eigen::VectorXd differentiate_proxy(const ModelHandler & model, + const VectorXd_fx & q1, + const VectorXd_fx & q2) + { + return differentiate(*model,q1,q2); + } + + static Eigen::VectorXd distance_proxy(const ModelHandler & model, + const VectorXd_fx & q1, + const VectorXd_fx & q2) + { + return distance(*model,q1,q2); + } + + static Eigen::VectorXd randomConfiguration_proxy(const ModelHandler & model, + const VectorXd_fx & lowerPosLimit, + const VectorXd_fx & upperPosLimit) + { + return randomConfiguration(*model, lowerPosLimit, upperPosLimit); + } + + void exposeJointsAlgo() + { + bp::def("integrate",integrate_proxy, + bp::args("Model", + "Configuration q (size Model::nq)", + "Velocity v (size Model::nv)"), + "Integrate the model for a tangent vector during one unit time ."); + + bp::def("interpolate",interpolate_proxy, + bp::args("Model", + "Configuration q1 (size Model::nq)", + "Configuration q2 (size Model::nq)", + "Double u"), + "Interpolate the model between two configurations."); + bp::def("differentiate",differentiate_proxy, + bp::args("Model", + "Configuration q1 (size Model::nq)", + "Configuration q2 (size Model::nq)"), + "Difference between two configurations, ie. the tangent vector that must be integrated during one unit time" + "to go from q1 to q2"); + bp::def("distance",distance_proxy, + bp::args("Model", + "Configuration q1 (size Model::nq)", + "Configuration q2 (size Model::nq)"), + "Distance between two configurations "); + bp::def("randomConfiguration",randomConfiguration_proxy, + bp::args("Model", + "Joint lower limits (size Model::nq)", + "Joint upper limits (size Model::nq)"), + "Generate a random configuration ensuring provied joint limits are respected "); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-kinematics.cpp b/bindings/python/algorithm/expose-kinematics.cpp new file mode 100644 index 000000000..00a10c77d --- /dev/null +++ b/bindings/python/algorithm/expose-kinematics.cpp @@ -0,0 +1,77 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/kinematics.hpp" + +namespace se3 +{ + namespace python + { + + static void fk_0_proxy(const ModelHandler & model, + DataHandler & data, + const VectorXd_fx & q) + { + forwardKinematics(*model,*data,q); + } + + static void fk_1_proxy(const ModelHandler& model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & qdot ) + { + forwardKinematics(*model,*data,q,qdot); + } + + + static void fk_2_proxy(const ModelHandler& model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & v, + const VectorXd_fx & a) + { + forwardKinematics(*model,*data,q,v,a); + } + + void exposeKinematics() + { + + bp::def("forwardKinematics",fk_0_proxy, + bp::args("Model","Data", + "Configuration q (size Model::nq)"), + "Compute the placements of all the frames of the kinematic " + "tree and put the results in data."); + + bp::def("forwardKinematics",fk_1_proxy, + bp::args("Model","Data", + "Configuration q (size Model::nq)", + "Velocity v (size Model::nv)"), + "Compute the placements and spatial velocities of all the frames of the kinematic " + "tree and put the results in data."); + + bp::def("forwardKinematics",fk_2_proxy, + bp::args("Model","Data", + "Configuration q (size Model::nq)", + "Velocity v (size Model::nv)", + "Acceleration a (size Model::nv)"), + "Compute the placements, spatial velocities and spatial accelerations of all the frames of the kinematic " + "tree and put the results in data."); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithm/expose-rnea.cpp b/bindings/python/algorithm/expose-rnea.cpp new file mode 100644 index 000000000..ad64289f7 --- /dev/null +++ b/bindings/python/algorithm/expose-rnea.cpp @@ -0,0 +1,60 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/algorithm/algorithms.hpp" +#include "pinocchio/algorithm/rnea.hpp" + +namespace se3 +{ + namespace python + { + static Eigen::VectorXd rnea_proxy(const ModelHandler& model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & v, + const VectorXd_fx & a) + { + return rnea(*model,*data,q,v,a); + } + + static Eigen::VectorXd nle_proxy(const ModelHandler& model, + DataHandler & data, + const VectorXd_fx & q, + const VectorXd_fx & v) + { + return nonLinearEffects(*model,*data,q,v); + } + + void exposeRNEA() + { + bp::def("rnea",rnea_proxy, + bp::args("Model","Data", + "Configuration q (size Model::nq)", + "Velocity v (size Model::nv)", + "Acceleration a (size Model::nv)"), + "Compute the RNEA, put the result in Data and return it."); + + bp::def("nle",nle_proxy, + bp::args("Model","Data", + "Configuration q (size Model::nq)", + "Velocity v (size Model::nv)"), + "Compute the Non Linear Effects (coriolis, centrifugal and gravitational effects), put the result in Data and return it."); + + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/algorithms.hpp b/bindings/python/algorithms.hpp deleted file mode 100644 index 847c2fe51..000000000 --- a/bindings/python/algorithms.hpp +++ /dev/null @@ -1,579 +0,0 @@ -// -// Copyright (c) 2015-2016 CNRS -// -// This file is part of Pinocchio -// Pinocchio is free software: you can redistribute it -// and/or modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation, either version -// 3 of the License, or (at your option) any later version. -// -// Pinocchio is distributed in the hope that it will be -// useful, but WITHOUT ANY WARRANTY; without even the implied warranty -// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -// General Lesser Public License for more details. You should have -// received a copy of the GNU Lesser General Public License along with -// Pinocchio If not, see -// <http://www.gnu.org/licenses/>. - -#ifndef __se3_python_algorithm_hpp__ -#define __se3_python_algorithm_hpp__ - -#include <eigenpy/exception.hpp> -#include <eigenpy/eigenpy.hpp> - -#include "pinocchio/python/model.hpp" -#include "pinocchio/python/data.hpp" - -#include "pinocchio/algorithm/rnea.hpp" -#include "pinocchio/algorithm/crba.hpp" -#include "pinocchio/algorithm/aba.hpp" -#include "pinocchio/algorithm/dynamics.hpp" -#include "pinocchio/algorithm/kinematics.hpp" -#include "pinocchio/algorithm/jacobian.hpp" -#include "pinocchio/algorithm/frames.hpp" -#include "pinocchio/algorithm/center-of-mass.hpp" -#include "pinocchio/algorithm/energy.hpp" -#include "pinocchio/algorithm/joint-configuration.hpp" -#include "pinocchio/algorithm/compute-all-terms.hpp" - -#include "pinocchio/multibody/geometry.hpp" -#include "pinocchio/python/geometry-model.hpp" -#include "pinocchio/python/geometry-data.hpp" -#include "pinocchio/algorithm/geometry.hpp" - - -namespace se3 -{ - namespace python - { - struct AlgorithmsPythonVisitor - { - typedef eigenpy::UnalignedEquivalent<Eigen::VectorXd>::type VectorXd_fx; - typedef eigenpy::UnalignedEquivalent<Eigen::MatrixXd>::type MatrixXd_fx; - - static Eigen::VectorXd rnea_proxy( const ModelHandler& model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & v, - const VectorXd_fx & a ) - { return rnea(*model,*data,q,v,a); } - - static Eigen::VectorXd nle_proxy( const ModelHandler& model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & v) - { return nonLinearEffects(*model,*data,q,v); } - - static Eigen::MatrixXd crba_proxy(const ModelHandler& model, - DataHandler & data, - const VectorXd_fx & q) - { - data->M.fill(0); - crba(*model,*data,q); - data->M.triangularView<Eigen::StrictlyLower>() - = data->M.transpose().triangularView<Eigen::StrictlyLower>(); - return data->M; - } - - static Data::Matrix6x ccrba_proxy(const ModelHandler& model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & v) - { - ccrba(*model,*data,q,v); - return data->Ag; - } - - static Eigen::MatrixXd aba_proxy(const ModelHandler & model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & v, - const VectorXd_fx & tau) - { - aba(*model,*data,q,v,tau); - return data->ddq; - } - - static Eigen::MatrixXd fd_llt_proxy(const ModelHandler & model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & v, - const VectorXd_fx & tau, - const eigenpy::MatrixXd_fx & J, - const VectorXd_fx & gamma, - const bool update_kinematics = true) - { - forwardDynamics(*model,*data,q,v,tau,J,gamma,update_kinematics); - return data->ddq; - } - - static Eigen::MatrixXd id_llt_proxy(const ModelHandler & model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & v_before, - const eigenpy::MatrixXd_fx & J, - const double r_coeff, - const bool update_kinematics = true) - { - impulseDynamics(*model,*data,q,v_before,J,r_coeff,update_kinematics); - return data->dq_after; - } - - static SE3::Vector3 - com_0_proxy(const ModelHandler& model, - DataHandler & data, - const VectorXd_fx & q, - const bool updateKinematics = true) - { - return centerOfMass(*model,*data,q, - true, - updateKinematics); - } - - static SE3::Vector3 - com_1_proxy(const ModelHandler& model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & v, - const bool updateKinematics = true) - { - return centerOfMass(*model,*data,q,v, - true, - updateKinematics); - } - - static SE3::Vector3 - com_2_proxy(const ModelHandler & model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & v, - const VectorXd_fx & a, - const bool updateKinematics = true) - { - return centerOfMass(*model,*data,q,v,a, - true, - updateKinematics); - } - - static Data::Matrix3x - Jcom_proxy(const ModelHandler& model, - DataHandler & data, - const VectorXd_fx & q) - { return jacobianCenterOfMass(*model,*data,q); } - - static Data::Matrix6x - jacobian_proxy(const ModelHandler & model, - DataHandler & data, - const VectorXd_fx & q, - Model::JointIndex jointId, - bool local, - bool update_geometry) - { - Data::Matrix6x J( 6,model->nv ); J.setZero(); - if (update_geometry) - computeJacobians( *model,*data,q ); - if(local) getJacobian<true> (*model, *data, jointId, J); - else getJacobian<false> (*model, *data, jointId, J); - return J; - } - - static Data::Matrix6x frame_jacobian_proxy(const ModelHandler & model, - DataHandler & data, - const VectorXd_fx & q, - Model::FrameIndex frame_id, - bool local, - bool update_geometry - ) - { - Data::Matrix6x J( 6,model->nv ); J.setZero(); - - if (update_geometry) - computeJacobians( *model,*data,q ); - - if(local) getFrameJacobian<true> (*model, *data, frame_id, J); - else getFrameJacobian<false> (*model, *data, frame_id, J); - - return J; - } - - static void compute_jacobians_proxy(const ModelHandler& model, - DataHandler & data, - const VectorXd_fx & q) - { - computeJacobians( *model,*data,q ); - } - - static void fk_0_proxy(const ModelHandler & model, - DataHandler & data, - const VectorXd_fx & q) - { - forwardKinematics(*model,*data,q); - } - - static void fk_1_proxy(const ModelHandler& model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & qdot ) - { - forwardKinematics(*model,*data,q,qdot); - } - - - static void frames_fk_0_proxy(const ModelHandler& model, - DataHandler & data, - const VectorXd_fx & q - ) - { - framesForwardKinematics( *model,*data,q ); - } - - static void fk_2_proxy(const ModelHandler& model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & v, - const VectorXd_fx & a) - { - forwardKinematics(*model,*data,q,v,a); - } - - static void computeAllTerms_proxy(const ModelHandler & model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & v) - { - data->M.fill(0); - computeAllTerms(*model,*data,q,v); - data->M.triangularView<Eigen::StrictlyLower>() - = data->M.transpose().triangularView<Eigen::StrictlyLower>(); - } - - - static double kineticEnergy_proxy(const ModelHandler & model, - DataHandler & data, - const VectorXd_fx & q, - const VectorXd_fx & v, - const bool update_kinematics = true) - { - return kineticEnergy(*model,*data,q,v,update_kinematics); - } - - static double potentialEnergy_proxy(const ModelHandler & model, - DataHandler & data, - const VectorXd_fx & q, - const bool update_kinematics = true) - { - return potentialEnergy(*model,*data,q,update_kinematics); - } - - static Eigen::VectorXd integrate_proxy(const ModelHandler & model, - const VectorXd_fx & q, - const VectorXd_fx & v) - { - return integrate(*model,q,v); - } - - static Eigen::VectorXd interpolate_proxy(const ModelHandler & model, - const VectorXd_fx & q1, - const VectorXd_fx & q2, - const double u) - { - return interpolate(*model,q1,q2,u); - } - - static Eigen::VectorXd differentiate_proxy(const ModelHandler & model, - const VectorXd_fx & q1, - const VectorXd_fx & q2) - { - return differentiate(*model,q1,q2); - } - - static Eigen::VectorXd distance_proxy(const ModelHandler & model, - const VectorXd_fx & q1, - const VectorXd_fx & q2) - { - return distance(*model,q1,q2); - } - - static Eigen::VectorXd randomConfiguration_proxy(const ModelHandler & model, - const VectorXd_fx & lowerPosLimit, - const VectorXd_fx & upperPosLimit) - { - return randomConfiguration(*model, lowerPosLimit, upperPosLimit); - } - - - - static void updateGeometryPlacements_proxy(const ModelHandler & model, - DataHandler & data, - const GeometryModelHandler & geom_model, - GeometryDataHandler & geom_data, - const VectorXd_fx & q - ) - { - return updateGeometryPlacements(*model, *data, *geom_model, *geom_data, q); - } -#ifdef WITH_HPP_FCL - static bool computeCollisions_proxy(GeometryDataHandler & data_geom, - const bool stopAtFirstCollision) - { - return computeCollisions(*data_geom, stopAtFirstCollision); - } - - static bool computeGeometryAndCollisions_proxy(const ModelHandler & model, - DataHandler & data, - const GeometryModelHandler & model_geom, - GeometryDataHandler & data_geom, - const VectorXd_fx & q, - const bool stopAtFirstCollision) - { - return computeCollisions(*model,*data,*model_geom, *data_geom, q, stopAtFirstCollision); - } - - static void computeDistances_proxy(GeometryDataHandler & data_geom) - { - computeDistances(*data_geom); - } - - static void computeGeometryAndDistances_proxy( const ModelHandler & model, - DataHandler & data, - const GeometryModelHandler & model_geom, - GeometryDataHandler & data_geom, - const Eigen::VectorXd & q - ) - { - computeDistances(*model, *data, *model_geom, *data_geom, q); - } - -#endif // WITH_HPP_FCL - - - /* --- Expose --------------------------------------------------------- */ - static void expose() - { - bp::def("rnea",rnea_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Velocity v (size Model::nv)", - "Acceleration a (size Model::nv)"), - "Compute the RNEA, put the result in Data and return it."); - - bp::def("nle",nle_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Velocity v (size Model::nv)"), - "Compute the Non Linear Effects (coriolis, centrifugal and gravitational effects), put the result in Data and return it."); - - bp::def("crba",crba_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)"), - "Compute CRBA, put the result in Data and return it."); - - bp::def("ccrba",ccrba_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Velocity v (size Model::nv)"), - "Compute the centroidal mapping, the centroidal momentum and the Centroidal Composite Rigid Body Inertia, put the result in Data and return the centroidal mapping."); - - bp::def("aba",aba_proxy, - bp::args("Model","Data", - "Joint configuration q (size Model::nq)", - "Joint velocity v (size Model::nv)", - "Joint torque tau (size Model::nv)"), - "Compute ABA, put the result in Data::ddq and return it."); - - bp::def("forwardDynamics",fd_llt_proxy, - bp::args("Model","Data", - "Joint configuration q (size Model::nq)", - "Joint velocity v (size Model::nv)", - "Joint torque tau (size Model::nv)", - "Contact Jacobian J (size nb_constraint * Model::nv)", - "Contact drift gamma (size nb_constraint)", - "Update kinematics (if true, it updates the dynamic variable according to the current state)"), - "Solve the forward dynamics problem with contacts, put the result in Data::ddq and return it. The contact forces are stored in data.lambda_c"); - - bp::def("impactDynamics",id_llt_proxy, - bp::args("Model","Data", - "Joint configuration q (size Model::nq)", - "Joint velocity before impact v_before (size Model::nv)", - "Contact Jacobian J (size nb_constraint * Model::nv)", - "Coefficient of restitution r_coeff (0 = rigid impact; 1 = fully elastic impact.", - "Update kinematics (if true, it updates only the joint space inertia matrix)"), - "Solve the impact dynamics problem with contacts, put the result in Data::dq_after and return it. The contact impulses are stored in data.impulse_c"); - - bp::def("centerOfMass",com_0_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Update kinematics"), - "Compute the center of mass, putting the result in Data and return it."); - - bp::def("centerOfMass",com_1_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Velocity v (size Model::nv)", - "Update kinematics"), - "Compute the center of mass position and velocuty by storing the result in Data" - "and return the center of mass position of the full model expressed in the world frame."); - - bp::def("centerOfMass",com_2_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Velocity v (size Model::nv)", - "Acceleration a (size Model::nv)", - "Update kinematics"), - "Compute the center of mass position, velocity and acceleration by storing the result in Data" - "and return the center of mass position of the full model expressed in the world frame."); - - bp::def("jacobianCenterOfMass",Jcom_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)"), - "Compute the jacobian of the center of mass, put the result in Data and return it."); - - - bp::def("framesKinematics",frames_fk_0_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)"), - "Compute the placements of all the operational frames " - "and put the results in data."); - - bp::def("forwardKinematics",fk_0_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)"), - "Compute the placements of all the frames of the kinematic " - "tree and put the results in data."); - - bp::def("forwardKinematics",fk_1_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Velocity v (size Model::nv)"), - "Compute the placements and spatial velocities of all the frames of the kinematic " - "tree and put the results in data."); - - bp::def("forwardKinematics",fk_2_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Velocity v (size Model::nv)", - "Acceleration a (size Model::nv)"), - "Compute the placements, spatial velocities and spatial accelerations of all the frames of the kinematic " - "tree and put the results in data."); - - bp::def("computeAllTerms",computeAllTerms_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Velocity v (size Model::nv)"), - "Compute all the terms M, non linear effects and Jacobians in" - "in the same loop and put the results in data."); - - bp::def("jacobian",jacobian_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Joint ID (int)", - "frame (true = local, false = world)", - "update_geometry (true = update the value of the total jacobian)"), - "Calling computeJacobians then getJacobian, return the result. Attention: the " - "function computes indeed all the jacobians of the model, even if just outputing " - "the demanded one if update_geometry is set to false. It is therefore outrageously costly wrt a dedicated " - "call. Function to be used only for prototyping."); - - bp::def("frameJacobian",frame_jacobian_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Operational frame ID (int)", - "frame (true = local, false = world)", - "update_geometry (true = recompute the kinematics)"), - "Call computeJacobians if update_geometry is true. If not, user should call computeJacobians first." - "Then call getJacobian and return the resulted jacobian matrix. Attention: if update_geometry is true, the " - "function computes all the jacobians of the model. It is therefore outrageously costly wrt a dedicated " - "call. Use only with update_geometry for prototyping."); - - bp::def("computeJacobians",compute_jacobians_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)"), - "Calling computeJacobians"); - - - bp::def("kineticEnergy",kineticEnergy_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Velocity v (size Model::nv)", - "Update kinematics (bool)"), - "Compute the kinematic energy of the model for the " - "given joint configuration and velocity and store it " - " in data.kinetic_energy. By default, the kinematics of model is updated."); - - bp::def("potentialEnergy",potentialEnergy_proxy, - bp::args("Model","Data", - "Configuration q (size Model::nq)", - "Update kinematics (bool)"), - "Compute the potential energy of the model for the " - "given the joint configuration and store it " - " in data.potential_energy. By default, the kinematics of model is updated."); - - bp::def("integrate",integrate_proxy, - bp::args("Model", - "Configuration q (size Model::nq)", - "Velocity v (size Model::nv)"), - "Integrate the model for a tangent vector during one unit time ."); - - bp::def("interpolate",interpolate_proxy, - bp::args("Model", - "Configuration q1 (size Model::nq)", - "Configuration q2 (size Model::nq)", - "Double u"), - "Interpolate the model between two configurations."); - bp::def("differentiate",differentiate_proxy, - bp::args("Model", - "Configuration q1 (size Model::nq)", - "Configuration q2 (size Model::nq)"), - "Difference between two configurations, ie. the tangent vector that must be integrated during one unit time" - "to go from q1 to q2"); - bp::def("distance",distance_proxy, - bp::args("Model", - "Configuration q1 (size Model::nq)", - "Configuration q2 (size Model::nq)"), - "Distance between two configurations "); - bp::def("randomConfiguration",randomConfiguration_proxy, - bp::args("Model", - "Joint lower limits (size Model::nq)", - "Joint upper limits (size Model::nq)"), - "Generate a random configuration ensuring provied joint limits are respected "); - // bp::def("randomConfiguration",randomConfiguration_proxy, - // bp::args("Model"), - // "Generate a random configuration ensuring Model's joint limits are respected "); - - bp::def("updateGeometryPlacements",updateGeometryPlacements_proxy, - bp::args("Model", "Data", "GeometryModel", "GeometryData", "Configuration q (size Model::nq)"), - "Update the placement of the collision objects according to the current configuration." - "The algorithm also updates the current placement of the joint in Data." - ); - -#ifdef WITH_HPP_FCL - bp::def("computeCollisions",computeCollisions_proxy, - bp::args("GeometryData","bool"), - "Determine if collision pairs are effectively in collision." - ); - - bp::def("computeGeometryAndCollisions",computeGeometryAndCollisions_proxy, - bp::args("Model","Data","GeometryModel","GeometryData","Configuration q (size Model::nq)", "bool"), - "Update the geometry for a given configuration and" - "determine if all collision pairs are effectively in collision or not." - ); - - bp::def("computeDistances",computeDistances_proxy, - bp::args("GeometryData"), - "Compute the distance between each collision pair." - ); - - bp::def("computeGeometryAndDistances",computeGeometryAndDistances_proxy, - bp::args("Model","Data","GeometryModel","GeometryData","Configuration q (size Model::nq)"), - "Update the geometry for a given configuration and" - "compute the distance between each collision pair" - ); - -#endif // WITH_HPP_FCL - } - }; - - }} // namespace se3::python - -#endif // ifndef __se3_python_data_hpp__ - diff --git a/bindings/python/data.hpp b/bindings/python/data.hpp index e82706bf5..f403f4211 100644 --- a/bindings/python/data.hpp +++ b/bindings/python/data.hpp @@ -18,11 +18,12 @@ #ifndef __se3_python_data_hpp__ #define __se3_python_data_hpp__ -#include <eigenpy/exception.hpp> -#include <eigenpy/eigenpy.hpp> #include "pinocchio/multibody/model.hpp" +#include "pinocchio/bindings/python/handler.hpp" -#include <boost/shared_ptr.hpp> +#include <eigenpy/exception.hpp> +#include <eigenpy/eigenpy.hpp> +#include <boost/python/suite/indexing/vector_indexing_suite.hpp> namespace se3 { diff --git a/bindings/python/explog.hpp b/bindings/python/explog.hpp index a4aa42c73..057de820c 100644 --- a/bindings/python/explog.hpp +++ b/bindings/python/explog.hpp @@ -22,8 +22,8 @@ # include <eigenpy/eigenpy.hpp> # include "pinocchio/spatial/explog.hpp" -# include "pinocchio/python/se3.hpp" -# include "pinocchio/python/motion.hpp" +# include "pinocchio/bindings/python/se3.hpp" +# include "pinocchio/bindings/python/motion.hpp" namespace se3 { diff --git a/bindings/python/expose-SE3.cpp b/bindings/python/expose-SE3.cpp new file mode 100644 index 000000000..fe1a2ebcc --- /dev/null +++ b/bindings/python/expose-SE3.cpp @@ -0,0 +1,34 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/se3.hpp" +#include "pinocchio/bindings/python/eigen_container.hpp" + +namespace se3 +{ + namespace python + { + + void exposeSE3() + { + SE3PythonVisitor<SE3>::expose(); + PyWraperForAlignedStdVector<SE3>::expose("StdVect_SE3"); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/expose-data.cpp b/bindings/python/expose-data.cpp new file mode 100644 index 000000000..8d8efbefd --- /dev/null +++ b/bindings/python/expose-data.cpp @@ -0,0 +1,32 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/data.hpp" + +namespace se3 +{ + namespace python + { + + void exposeData() + { + DataPythonVisitor::expose(); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/expose-explog.cpp b/bindings/python/expose-explog.cpp new file mode 100644 index 000000000..75575e550 --- /dev/null +++ b/bindings/python/expose-explog.cpp @@ -0,0 +1,33 @@ +// +// Copyright (c) 2015-2016 CNRS +// Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France. +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/explog.hpp" + +namespace se3 +{ + namespace python + { + + void exposeExplog() + { + ExplogPythonVisitor::expose(); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/expose-force.cpp b/bindings/python/expose-force.cpp new file mode 100644 index 000000000..955bcac89 --- /dev/null +++ b/bindings/python/expose-force.cpp @@ -0,0 +1,34 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/force.hpp" +#include "pinocchio/bindings/python/eigen_container.hpp" + +namespace se3 +{ + namespace python + { + + void exposeForce() + { + ForcePythonVisitor<Force>::expose(); + PyWraperForAlignedStdVector<Force>::expose("StdVect_Force"); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/expose-frame.cpp b/bindings/python/expose-frame.cpp new file mode 100644 index 000000000..7f0f44a66 --- /dev/null +++ b/bindings/python/expose-frame.cpp @@ -0,0 +1,32 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/frame.hpp" + +namespace se3 +{ + namespace python + { + + void exposeFrame() + { + FramePythonVisitor::expose(); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/expose-geometry.cpp b/bindings/python/expose-geometry.cpp new file mode 100644 index 000000000..313818e00 --- /dev/null +++ b/bindings/python/expose-geometry.cpp @@ -0,0 +1,37 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/geometry-object.hpp" +#include "pinocchio/bindings/python/geometry-model.hpp" +#include "pinocchio/bindings/python/geometry-data.hpp" + +namespace se3 +{ + namespace python + { + + void exposeGeometry() + { + GeometryObjectPythonVisitor::expose(); + CollisionPairPythonVisitor::expose(); + GeometryModelPythonVisitor::expose(); + GeometryDataPythonVisitor::expose(); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/expose-inertia.cpp b/bindings/python/expose-inertia.cpp new file mode 100644 index 000000000..261551ddc --- /dev/null +++ b/bindings/python/expose-inertia.cpp @@ -0,0 +1,34 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/inertia.hpp" +#include "pinocchio/bindings/python/eigen_container.hpp" + +namespace se3 +{ + namespace python + { + + void exposeInertia() + { + InertiaPythonVisitor<Inertia>::expose(); + PyWraperForAlignedStdVector<Inertia>::expose("StdVec_Inertia"); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/expose-joints.cpp b/bindings/python/expose-joints.cpp new file mode 100644 index 000000000..014ecfb8e --- /dev/null +++ b/bindings/python/expose-joints.cpp @@ -0,0 +1,45 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/joint-derived.hpp" +#include "pinocchio/bindings/python/joints-variant.hpp" +#include "pinocchio/bindings/python/joint.hpp" + +#include <boost/python/suite/indexing/vector_indexing_suite.hpp> + +namespace se3 +{ + namespace python + { + + static void exposeVariants() + { + boost::mpl::for_each<JointModelVariant::types>(exposer()); + bp::to_python_converter<se3::JointModelVariant, jointModelVariantVisitor>(); + } + + void exposeJoints() + { + exposeVariants(); + JointModelPythonVisitor::expose(); + bp::class_<JointModelVector>("StdVec_JointModelVector") + .def(bp::vector_indexing_suite<JointModelVector,true>()); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/expose-model.cpp b/bindings/python/expose-model.cpp new file mode 100644 index 000000000..ba5dccc55 --- /dev/null +++ b/bindings/python/expose-model.cpp @@ -0,0 +1,32 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/model.hpp" + +namespace se3 +{ + namespace python + { + + void exposeModel() + { + ModelPythonVisitor::expose(); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/expose-motion.cpp b/bindings/python/expose-motion.cpp new file mode 100644 index 000000000..007c4da2a --- /dev/null +++ b/bindings/python/expose-motion.cpp @@ -0,0 +1,34 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/motion.hpp" +#include "pinocchio/bindings/python/eigen_container.hpp" + +namespace se3 +{ + namespace python + { + + void exposeMotion() + { + MotionPythonVisitor<Motion>::expose(); + PyWraperForAlignedStdVector<Motion>::expose("StdVect_Motion"); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/expose-parsers.cpp b/bindings/python/expose-parsers.cpp new file mode 100644 index 000000000..693cc6646 --- /dev/null +++ b/bindings/python/expose-parsers.cpp @@ -0,0 +1,32 @@ +// +// Copyright (c) 2015-2016 CNRS +// +// This file is part of Pinocchio +// Pinocchio is free software: you can redistribute it +// and/or modify it under the terms of the GNU Lesser General Public +// License as published by the Free Software Foundation, either version +// 3 of the License, or (at your option) any later version. +// +// Pinocchio is distributed in the hope that it will be +// useful, but WITHOUT ANY WARRANTY; without even the implied warranty +// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU +// General Lesser Public License for more details. You should have +// received a copy of the GNU Lesser General Public License along with +// Pinocchio If not, see +// <http://www.gnu.org/licenses/>. + +#include "pinocchio/bindings/python/python.hpp" +#include "pinocchio/bindings/python/parsers.hpp" + +namespace se3 +{ + namespace python + { + + void exposeParsers() + { + ParsersPythonVisitor::expose(); + } + + } // namespace python +} // namespace se3 diff --git a/bindings/python/frame.hpp b/bindings/python/frame.hpp index a88e25147..4a1984655 100644 --- a/bindings/python/frame.hpp +++ b/bindings/python/frame.hpp @@ -23,6 +23,7 @@ #include <boost/python/suite/indexing/vector_indexing_suite.hpp> +#include "pinocchio/bindings/python/se3.hpp" #include "pinocchio/multibody/frame.hpp" #include "pinocchio/multibody/model.hpp" @@ -65,7 +66,7 @@ namespace se3 } - static SE3_fx getPlacementWrtParentJoint( const Frame & self) { return self.placement; } + static SE3_fx getPlacementWrtParentJoint(const Frame & self) { return self.placement; } static void setPlacementWrtParentJoint(Frame & self, const SE3_fx & placement) { self.placement = placement; } static void expose() diff --git a/bindings/python/geometry-data.hpp b/bindings/python/geometry-data.hpp index 5d4a67bfb..e8b380f0d 100644 --- a/bindings/python/geometry-data.hpp +++ b/bindings/python/geometry-data.hpp @@ -22,11 +22,11 @@ #include <eigenpy/exception.hpp> #include <eigenpy/eigenpy.hpp> -#include "pinocchio/python/se3.hpp" -#include "pinocchio/python/eigen_container.hpp" -#include "pinocchio/python/handler.hpp" -#include "pinocchio/python/data.hpp" -#include "pinocchio/python/geometry-model.hpp" +#include "pinocchio/bindings/python/se3.hpp" +#include "pinocchio/bindings/python/eigen_container.hpp" +#include "pinocchio/bindings/python/handler.hpp" +#include "pinocchio/bindings/python/data.hpp" +#include "pinocchio/bindings/python/geometry-model.hpp" namespace se3 { diff --git a/bindings/python/geometry-model.hpp b/bindings/python/geometry-model.hpp index 13c6c9bca..1dcc106a5 100644 --- a/bindings/python/geometry-model.hpp +++ b/bindings/python/geometry-model.hpp @@ -22,9 +22,9 @@ #include <eigenpy/exception.hpp> #include <eigenpy/eigenpy.hpp> -#include "pinocchio/python/se3.hpp" -#include "pinocchio/python/eigen_container.hpp" -#include "pinocchio/python/handler.hpp" +#include "pinocchio/bindings/python/se3.hpp" +#include "pinocchio/bindings/python/eigen_container.hpp" +#include "pinocchio/bindings/python/handler.hpp" #include "pinocchio/multibody/geometry.hpp" @@ -33,18 +33,18 @@ namespace se3 namespace python { namespace bp = boost::python; - + typedef Handler<GeometryModel> GeometryModelHandler; - + struct GeometryModelPythonVisitor - : public boost::python::def_visitor< GeometryModelPythonVisitor > + : public boost::python::def_visitor< GeometryModelPythonVisitor > { public: typedef eigenpy::UnalignedEquivalent<SE3>::type SE3_fx; public: - + /* --- Convert From C++ to Python ------------------------------------- */ // static PyObject* convert(Model const& modelConstRef) // { @@ -55,10 +55,10 @@ namespace se3 { return boost::python::incref(boost::python::object(GeometryModelHandler(ptr)).ptr()); } - + /* --- Exposing C++ API to python through the handler ----------------- */ - template<class PyClass> - void visit(PyClass& cl) const + template<class PyClass> + void visit(PyClass& cl) const { cl .add_property("ngeoms", &GeometryModelPythonVisitor::ngeoms) @@ -102,68 +102,64 @@ namespace se3 } static Index ngeoms( GeometryModelHandler & m ) { return m->ngeoms; } - static GeomIndex getGeometryId( const GeometryModelHandler & gmodelPtr, const std::string & name ) { return gmodelPtr->getGeometryId(name); } static bool existGeometryName(const GeometryModelHandler & gmodelPtr, const std::string & name) { return gmodelPtr->existGeometryName(name);} static std::string getGeometryName(const GeometryModelHandler & gmodelPtr, const GeomIndex index) { return gmodelPtr->getGeometryName(index);} - + static std::vector<GeometryObject> & geometryObjects( GeometryModelHandler & m ) { return m->geometryObjects; } #ifdef WITH_HPP_FCL static std::vector<CollisionPair> & collision_pairs( GeometryModelHandler & m ) { return m->collisionPairs; } - + static void addCollisionPair (GeometryModelHandler & m, const GeomIndex co1, const GeomIndex co2) { m->addCollisionPair(CollisionPair(co1, co2)); } - + static void addAllCollisionPairs (GeometryModelHandler & m) { m->addAllCollisionPairs(); } static void removeCollisionPair (GeometryModelHandler & m, const GeomIndex co1, const GeomIndex co2) { m->removeCollisionPair( CollisionPair(co1,co2) ); } - + static void removeAllCollisionPairs (GeometryModelHandler & m) - { m->removeAllCollisionPairs(); } - + { m->removeAllCollisionPairs(); } + static bool existCollisionPair (const GeometryModelHandler & m, const GeomIndex co1, const GeomIndex co2) { return m->existCollisionPair(CollisionPair(co1,co2)); } static Index findCollisionPair (const GeometryModelHandler & m, const GeomIndex co1, - const GeomIndex co2) + const GeomIndex co2) { return m->findCollisionPair( CollisionPair(co1,co2) ); } #endif // WITH_HPP_FCL static GeometryModelHandler maker_default() { return GeometryModelHandler(new GeometryModel(), true); } - - static std::string toString(const GeometryModelHandler& m) + + static std::string toString(const GeometryModelHandler& m) { std::ostringstream s; s << *m; return s.str(); } - + /* --- Expose --------------------------------------------------------- */ static void expose() { - - bp::enum_<GeometryType>("GeometryType") - .value("VISUAL",VISUAL) - .value("COLLISION",COLLISION) - .value("NONE",NONE) - ; - - bp::class_<GeometryModelHandler>("GeometryModel", - "Geometry model (const)", - bp::no_init) - .def(GeometryModelPythonVisitor()); - - bp::to_python_converter< GeometryModelHandler::SmartPtr_t,GeometryModelPythonVisitor >(); + + bp::enum_<GeometryType>("GeometryType") + .value("VISUAL",VISUAL) + .value("COLLISION",COLLISION) + .value("NONE",NONE) + ; + + bp::class_<GeometryModelHandler>("GeometryModel", + "Geometry model (const)", + bp::no_init) + .def(GeometryModelPythonVisitor()); + + bp::to_python_converter< GeometryModelHandler::SmartPtr_t,GeometryModelPythonVisitor >(); } - - + }; - - - }} // namespace se3::python + } // namespace python +} // namespace se3 #endif // ifndef __se3_python_geometry_model_hpp__ - diff --git a/bindings/python/geometry-object.hpp b/bindings/python/geometry-object.hpp index 4c2b40e3c..cd9506845 100644 --- a/bindings/python/geometry-object.hpp +++ b/bindings/python/geometry-object.hpp @@ -23,10 +23,10 @@ #include <boost/python/suite/indexing/vector_indexing_suite.hpp> +#include "pinocchio/bindings/python/se3.hpp" #include "pinocchio/multibody/model.hpp" #include "pinocchio/multibody/geometry.hpp" - namespace se3 { namespace python @@ -64,7 +64,6 @@ namespace se3 static SE3_fx getPlacementWrtParentJoint( const GeometryObject & self) { return self.placement; } static void setPlacementWrtParentJoint(GeometryObject & self, const SE3_fx & placement) { self.placement = placement; } - static void expose() { bp::class_<GeometryObject>("GeometryObject", @@ -78,7 +77,6 @@ namespace se3 .def(bp::vector_indexing_suite< std::vector<GeometryObject> >()); } - }; diff --git a/bindings/python/joint.hpp b/bindings/python/joint.hpp index 55a1b76c1..9014d720f 100644 --- a/bindings/python/joint.hpp +++ b/bindings/python/joint.hpp @@ -22,8 +22,6 @@ #include <eigenpy/eigenpy.hpp> #include "pinocchio/multibody/joint/joint.hpp" - - namespace se3 { namespace python diff --git a/bindings/python/joints-models.hpp b/bindings/python/joints-models.hpp index 9412d6471..6321e708a 100644 --- a/bindings/python/joints-models.hpp +++ b/bindings/python/joints-models.hpp @@ -22,8 +22,6 @@ #include <eigenpy/eigenpy.hpp> #include "pinocchio/multibody/joint/joint-variant.hpp" - - namespace se3 { namespace python diff --git a/bindings/python/joints-variant.hpp b/bindings/python/joints-variant.hpp index b60ea778e..beedbd6eb 100644 --- a/bindings/python/joints-variant.hpp +++ b/bindings/python/joints-variant.hpp @@ -21,7 +21,7 @@ #include <eigenpy/exception.hpp> #include <eigenpy/eigenpy.hpp> #include "pinocchio/multibody/joint/joint-variant.hpp" -#include "pinocchio/python/joints-models.hpp" +#include "pinocchio/bindings/python/joints-models.hpp" namespace se3 { @@ -53,14 +53,6 @@ namespace se3 } }; - // For the moment, only expose models of joint. Not data ( to do it, split exposer into exposerModels & exposer_Datas and do another for_each) - static void exposeVariants() - { - boost::mpl::for_each<JointModelVariant::types>(exposer()); - bp::to_python_converter<se3::JointModelVariant, jointModelVariantVisitor>(); - // bp::def("make_variant", se3::make_variant); - } - } // namespace python } // namespace se3 diff --git a/bindings/python/model.hpp b/bindings/python/model.hpp index 82112ebdc..80349e9b8 100644 --- a/bindings/python/model.hpp +++ b/bindings/python/model.hpp @@ -25,11 +25,11 @@ #include "pinocchio/multibody/model.hpp" #include "pinocchio/parsers/sample-models.hpp" -#include "pinocchio/python/se3.hpp" -#include "pinocchio/python/eigen_container.hpp" -#include "pinocchio/python/handler.hpp" -#include "pinocchio/python/motion.hpp" -#include "pinocchio/python/inertia.hpp" +#include "pinocchio/bindings/python/se3.hpp" +#include "pinocchio/bindings/python/eigen_container.hpp" +#include "pinocchio/bindings/python/handler.hpp" +#include "pinocchio/bindings/python/motion.hpp" +#include "pinocchio/bindings/python/inertia.hpp" namespace se3 diff --git a/bindings/python/module.cpp b/bindings/python/module.cpp index aaba250ec..8f69cbf70 100644 --- a/bindings/python/module.cpp +++ b/bindings/python/module.cpp @@ -18,7 +18,7 @@ #include <eigenpy/eigenpy.hpp> #include <eigenpy/geometry.hpp> -#include "pinocchio/python/python.hpp" +#include "pinocchio/bindings/python/python.hpp" #include <iostream> @@ -48,6 +48,10 @@ BOOST_PYTHON_MODULE(libpinocchio_pywrap) se3::python::exposeExplog(); se3::python::exposeModel(); + se3::python::exposeFrame(); + se3::python::exposeData(); + se3::python::exposeGeometry(); + se3::python::exposeAlgorithms(); se3::python::exposeParsers(); } diff --git a/bindings/python/parsers.hpp b/bindings/python/parsers.hpp index b29c5064e..24179c921 100644 --- a/bindings/python/parsers.hpp +++ b/bindings/python/parsers.hpp @@ -1,4 +1,4 @@ -// + // // Copyright (c) 2015-2016 CNRS // // This file is part of Pinocchio @@ -21,15 +21,16 @@ #include <eigenpy/exception.hpp> #include <eigenpy/eigenpy.hpp> -#include "pinocchio/python/model.hpp" -#include "pinocchio/python/data.hpp" +#include "pinocchio/bindings/python/model.hpp" +#include "pinocchio/bindings/python/data.hpp" #ifdef WITH_URDFDOM #include "pinocchio/parsers/urdf.hpp" - #include "pinocchio/python/geometry-model.hpp" - #include "pinocchio/python/geometry-data.hpp" #endif + #include "pinocchio/bindings/python/geometry-model.hpp" + #include "pinocchio/bindings/python/geometry-data.hpp" + #ifdef WITH_LUA #include "pinocchio/parsers/lua.hpp" #endif // #ifdef WITH_LUA diff --git a/bindings/python/python.cpp b/bindings/python/python.cpp deleted file mode 100644 index bb42329b8..000000000 --- a/bindings/python/python.cpp +++ /dev/null @@ -1,92 +0,0 @@ -// -// Copyright (c) 2015 CNRS -// Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France. -// -// This file is part of Pinocchio -// Pinocchio is free software: you can redistribute it -// and/or modify it under the terms of the GNU Lesser General Public -// License as published by the Free Software Foundation, either version -// 3 of the License, or (at your option) any later version. -// -// Pinocchio is distributed in the hope that it will be -// useful, but WITHOUT ANY WARRANTY; without even the implied warranty -// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU -// General Lesser Public License for more details. You should have -// received a copy of the GNU Lesser General Public License along with -// Pinocchio If not, see -// <http://www.gnu.org/licenses/>. - -#include "pinocchio/python/python.hpp" -#include "pinocchio/python/se3.hpp" -#include "pinocchio/python/force.hpp" -#include "pinocchio/python/motion.hpp" -#include "pinocchio/python/inertia.hpp" -#include "pinocchio/python/joint-derived.hpp" -#include "pinocchio/python/joints-variant.hpp" -#include "pinocchio/python/joint.hpp" - -#include "pinocchio/python/frame.hpp" -#include "pinocchio/python/model.hpp" -#include "pinocchio/python/data.hpp" -#include "pinocchio/python/algorithms.hpp" -#include "pinocchio/python/parsers.hpp" -#include "pinocchio/python/explog.hpp" - -#include "pinocchio/python/geometry-object.hpp" -#include "pinocchio/python/geometry-model.hpp" -#include "pinocchio/python/geometry-data.hpp" - -namespace se3 -{ - namespace python - { - void exposeSE3() - { - SE3PythonVisitor<SE3>::expose(); - PyWraperForAlignedStdVector<SE3>::expose("StdVect_SE3"); - } - void exposeForce() - { - ForcePythonVisitor<Force>::expose(); - PyWraperForAlignedStdVector<Force>::expose("StdVec_Force"); - } - void exposeMotion() - { - MotionPythonVisitor<Motion>::expose(); - PyWraperForAlignedStdVector<Motion>::expose("StdVec_Motion"); - } - void exposeInertia() - { - InertiaPythonVisitor<Inertia>::expose(); - PyWraperForAlignedStdVector<Inertia>::expose("StdVec_Inertia"); - } - void exposeJoints() - { - exposeVariants(); - JointModelPythonVisitor::expose(); - bp::class_<JointModelVector>("StdVec_JointModelVector") - .def(bp::vector_indexing_suite<JointModelVector,true>()); - } - void exposeModel() - { - FramePythonVisitor::expose(); - ModelPythonVisitor::expose(); - DataPythonVisitor::expose(); - GeometryObjectPythonVisitor::expose(); - CollisionPairPythonVisitor::expose(); - GeometryModelPythonVisitor::expose(); - GeometryDataPythonVisitor::expose(); - } - void exposeAlgorithms() - { - AlgorithmsPythonVisitor::expose(); - } - void exposeParsers() - { - ParsersPythonVisitor::expose(); - } - void exposeExplog() - { - ExplogPythonVisitor::expose(); - } - }} // namespace se3::python diff --git a/bindings/python/python.hpp b/bindings/python/python.hpp index f799cf6c6..f87634f99 100644 --- a/bindings/python/python.hpp +++ b/bindings/python/python.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2015 CNRS +// Copyright (c) 2015-2016 CNRS // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France. // // This file is part of Pinocchio @@ -23,18 +23,30 @@ namespace se3 { namespace python { + // Expose spatial classes void exposeSE3(); void exposeForce(); void exposeMotion(); void exposeInertia(); - void exposeJoints(); void exposeExplog(); - + + // Expose multibody classes + void exposeJoints(); void exposeModel(); - void exposeAlgorithms(); + void exposeFrame(); + void exposeData(); + + // Expose geometry module + void exposeGeometry(); + + // Expose parsers void exposeParsers(); + + // Expose algorithms + void exposeAlgorithms(); - }} // namespace se3::python + } // namespace python +} // namespace se3 #endif // ifndef __se3_python_python_hpp__ -- GitLab