diff --git a/bindings/python/parsers/parsers.hpp b/bindings/python/parsers/parsers.hpp index 0c407473ee8efc5a2132e8862a243212c63ba20e..3a0dc8cd4f12f89fe987ef994b24a682c8a0a30a 100644 --- a/bindings/python/parsers/parsers.hpp +++ b/bindings/python/parsers/parsers.hpp @@ -127,18 +127,7 @@ namespace se3 return geometry_model; } - -#ifdef WITH_HPP_FCL - static void removeCollisionPairsFromSrdf(Model & model, - GeometryModel & geometry_model, - const std::string & filename, - bool verbose - ) - { - se3::srdf::removeCollisionPairsFromSrdf(model,geometry_model,filename,verbose); - } -#endif // #ifdef WITH_HPP_FCL #endif // #ifdef WITH_URDFDOM #ifdef WITH_LUA5 @@ -210,10 +199,16 @@ namespace se3 "Parse the URDF file given in input looking for the geometry of the given Model and return a proper pinocchio geometry model "); #ifdef WITH_HPP_FCL - bp::def("removeCollisionPairsFromSrdf",removeCollisionPairsFromSrdf, - bp::args("Model", "GeometryModel (where pairs are removed)","srdf filename (string)", "verbosity" - ), - "Parse an SRDF file in order to desactivate collision pairs for a specific GeometryData and GeometryModel "); + + bp::def("removeCollisionPairs", + static_cast<void (*)(const Model &, GeometryModel &, const std::string &, const bool)>(&srdf::removeCollisionPairs), + bp::args("Model", "GeometryModel (where pairs are removed)","srdf filename (string)", "verbosity"), + "Parse an SRDF file in order to desactivte collision pairs for a specific GeometryModel."); + + bp::def("removeCollisionPairsFromXML", + static_cast<void (*)(const Model &, GeometryModel &, const std::string &, const bool)>(&srdf::removeCollisionPairsFromXML), + bp::args("Model", "GeometryModel (where pairs are removed)","string containing the XML-SRDF", "verbosity"), + "Parse an SRDF file in order to desactivte collision pairs for a specific GeometryModel."); #endif // #ifdef WITH_HPP_FCL #endif // #ifdef WITH_URDFDOM @@ -226,14 +221,14 @@ namespace se3 "Parse the URDF file given in input and return a proper pinocchio model"); #endif // #ifdef WITH_LUA5 - bp::def("getNeutralConfigurationFromSrdf", - static_cast<Model::ConfigVectorType (*)(Model &, const std::string &, const bool)>(&srdf::getNeutralConfigurationFromSrdf), + bp::def("getNeutralConfiguration", + static_cast<Model::ConfigVectorType (*)(Model &, const std::string &, const bool)>(&srdf::getNeutralConfiguration), bp::args("Model for which we want the neutral config","srdf filename (string)", "verbosity" ), "Get the neutral configuration of a given model associated to a SRDF file"); - bp::def("loadRotorParamsFromSrdf", - static_cast<bool (*)(Model &, const std::string &, const bool)>(&srdf::loadRotorParamsFromSrdf), + bp::def("loadRotorParameters", + static_cast<bool (*)(Model &, const std::string &, const bool)>(&srdf::loadRotorParameters), bp::args("Model for which we are loading the rotor parameters", "SRDF filename (string)", "verbosity"), "Load the rotor parameters of a given model from an SRDF file.\n" diff --git a/bindings/python/scripts/deprecated.py b/bindings/python/scripts/deprecated.py index cc313b5b6efbcf163fe79ec4791fa3b267509aa8..2ec6d0f3582a96e1be5405e0e6780311a71fed68 100644 --- a/bindings/python/scripts/deprecated.py +++ b/bindings/python/scripts/deprecated.py @@ -79,3 +79,16 @@ def getJacobianTimeVariation(model,data,jointId,local): @deprecated("This function has been renamed difference and will be removed in release 1.4.0 of Pinocchio. Please change for new difference.") def differentiate(model,q0,q1): return se3.difference(model,q0,q1) + +@deprecated("This function has been renamed difference and will be removed in release 1.4.0 of Pinocchio. Please change for new getNeutralConfiguration function.") +def getNeutralConfigurationFromSrdf(model, filename, verbose): + return se3.getNeutralConfiguration(model,filename,verbose) + +@deprecated("This function has been renamed difference and will be removed in release 1.4.0 of Pinocchio. Please change for new loadRotorParameters function.") +def loadRotorParamsFromSrdf(model, filename, verbose): + return se3.loadRotorParams(model,filename,verbose) + +@deprecated("This function has been renamed difference and will be removed in release 1.4.0 of Pinocchio. Please change for new removeCollisionPairs function.") +def removeCollisionPairsFromSrdf(model, geomModel, filename, verbose): + return se3.removeCollisionPairs(model,geomModel,filename,verbose) + diff --git a/src/parsers/srdf.hpp b/src/parsers/srdf.hpp index 850b0e7bcea6277f273e224144c8884330d43077..40f90a32f47f81f2125cca6f1c36408bf97929ee 100644 --- a/src/parsers/srdf.hpp +++ b/src/parsers/srdf.hpp @@ -27,6 +27,7 @@ namespace se3 { #ifdef WITH_HPP_FCL + /// /// \brief Deactive all possible collision pairs mentioned in the SRDF file. /// It throws if the SRDF file is incorrect. @@ -38,27 +39,49 @@ namespace se3 /// \param[in] verbose Verbosity mode (print removed collision pairs and undefined link inside the model). /// template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> + void removeCollisionPairs(const ModelTpl<Scalar,Options,JointCollectionTpl> & model, + GeometryModel & geomModel, + const std::string & filename, + const bool verbose = false) throw (std::invalid_argument); + + /// \copydoc removeCollisionPairs + template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> + PINOCCHIO_DEPRECATED void removeCollisionPairsFromSrdf(const ModelTpl<Scalar,Options,JointCollectionTpl> & model, GeometryModel & geomModel, const std::string & filename, - const bool verbose = false) throw (std::invalid_argument); + const bool verbose = false) throw (std::invalid_argument) + { + removeCollisionPairs(model,geomModel,filename,verbose); + } + /// /// \brief Deactive all possible collision pairs mentioned in the SRDF file. /// /// \param[in] model Model of the kinematic tree. /// \param[in] geomModel Model of the geometries. /// \param[out] data_geom Data containing the active collision pairs. - /// \param[in] xmlString the SRDF string. + /// \param[in] xmlString constaining the XML SRDF string. /// \param[in] verbose Verbosity mode (print removed collision pairs and undefined link inside the model). /// template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> + void removeCollisionPairsFromXML(const ModelTpl<Scalar,Options,JointCollectionTpl> & model, + GeometryModel & geomModel, + const std::string & xmlString, + const bool verbose = false); + + /// \copydoc removeCollisionPairsFromXML + template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> + PINOCCHIO_DEPRECATED void removeCollisionPairsFromSrdfString(const ModelTpl<Scalar,Options,JointCollectionTpl> & model, GeometryModel & geomModel, const std::string & xmlString, - const bool verbose = false); + const bool verbose = false) + { + removeCollisionPairsFromXML(model,geomModel,xmlString,verbose); + } #endif // ifdef WITH_HPP_FCL - /// /// \brief Get the neutral configuration of a given model associated to a SRDF file. @@ -72,11 +95,19 @@ namespace se3 /// template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> typename ModelTpl<Scalar,Options,JointCollectionTpl>::ConfigVectorType + getNeutralConfiguration(ModelTpl<Scalar,Options,JointCollectionTpl> & model, + const std::string & filename, + const bool verbose = false) throw (std::invalid_argument); + + /// \copydoc se3::srdf::getNeutralConfiguration + template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> + PINOCCHIO_DEPRECATED + typename ModelTpl<Scalar,Options,JointCollectionTpl>::ConfigVectorType getNeutralConfigurationFromSrdf(ModelTpl<Scalar,Options,JointCollectionTpl> & model, const std::string & filename, - const bool verbose = false) throw (std::invalid_argument); - - + const bool verbose = false) throw (std::invalid_argument) + { return getNeutralConfiguration(model,filename,verbose); } + /// /// \brief Load the rotor params of a given model associated to a SRDF file. /// It throws if the SRDF file is incorrect. @@ -88,9 +119,19 @@ namespace se3 /// \return Boolean whether it loads or not. /// template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> + bool loadRotorParameters(ModelTpl<Scalar,Options,JointCollectionTpl> & model, + const std::string & filename, + const bool verbose = false) throw (std::invalid_argument); + + /// \copydoc se3::srdf::loadRotorParameters + template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> + PINOCCHIO_DEPRECATED bool loadRotorParamsFromSrdf(ModelTpl<Scalar,Options,JointCollectionTpl> & model, const std::string & filename, - const bool verbose) throw (std::invalid_argument); + const bool verbose = false) throw (std::invalid_argument) + { + return loadRotorParameters(model,filename,verbose); + } } } // namespace se3 diff --git a/src/parsers/srdf.hxx b/src/parsers/srdf.hxx index a0ff6a3b82282ab4579221a8425249f292c1fdd7..4bb92db7cdfcb00cfe7e87b005a9aebd4e4edbbd 100644 --- a/src/parsers/srdf.hxx +++ b/src/parsers/srdf.hxx @@ -107,10 +107,10 @@ namespace se3 } // namespace details template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> - void removeCollisionPairsFromSrdf(const ModelTpl<Scalar,Options,JointCollectionTpl> & model, - GeometryModel & geomModel, - const std::string & filename, - const bool verbose) throw (std::invalid_argument) + void removeCollisionPairs(const ModelTpl<Scalar,Options,JointCollectionTpl> & model, + GeometryModel & geomModel, + const std::string & filename, + const bool verbose) throw (std::invalid_argument) { // Check extension const std::string extension = filename.substr(filename.find_last_of('.')+1); @@ -132,10 +132,10 @@ namespace se3 } template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> - void removeCollisionPairsFromSrdfString(const ModelTpl<Scalar,Options,JointCollectionTpl> & model, - GeometryModel & geomModel, - const std::string & xmlString, - const bool verbose) + void removeCollisionPairsFromXML(const ModelTpl<Scalar,Options,JointCollectionTpl> & model, + GeometryModel & geomModel, + const std::string & xmlString, + const bool verbose) { std::istringstream srdf_stream(xmlString); details::removeCollisionPairs(model, geomModel, srdf_stream, verbose); @@ -144,9 +144,9 @@ namespace se3 #endif // ifdef WITH_HPP_FCL template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> - bool loadRotorParamsFromSrdf(ModelTpl<Scalar,Options,JointCollectionTpl> & model, - const std::string & filename, - const bool verbose) throw (std::invalid_argument) + bool loadRotorParameters(ModelTpl<Scalar,Options,JointCollectionTpl> & model, + const std::string & filename, + const bool verbose) throw (std::invalid_argument) { typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model; typedef typename Model::JointModel JointModel; @@ -216,9 +216,9 @@ namespace se3 template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl> typename ModelTpl<Scalar,Options,JointCollectionTpl>::ConfigVectorType - getNeutralConfigurationFromSrdf(ModelTpl<Scalar,Options,JointCollectionTpl> & model, - const std::string & filename, - const bool verbose) throw (std::invalid_argument) + getNeutralConfiguration(ModelTpl<Scalar,Options,JointCollectionTpl> & model, + const std::string & filename, + const bool verbose) throw (std::invalid_argument) { typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model; typedef typename Model::JointModel JointModel; diff --git a/unittest/srdf.cpp b/unittest/srdf.cpp index f033d90ac6025f501edc86d956b283884fa75178..bf08d2a4b8d7a57ea563920035f729f2068c31cd 100644 --- a/unittest/srdf.cpp +++ b/unittest/srdf.cpp @@ -28,7 +28,7 @@ using namespace std; BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE ) -BOOST_AUTO_TEST_CASE(removeCollisionPairs) +BOOST_AUTO_TEST_CASE(test_removeCollisionPairs) { using namespace se3::urdf; using namespace se3::srdf; @@ -47,7 +47,7 @@ BOOST_AUTO_TEST_CASE(removeCollisionPairs) const size_t num_init_col_pairs = geom_model.collisionPairs.size(); - removeCollisionPairsFromSrdf(model,geom_model,srdf_filename,false); + removeCollisionPairs(model,geom_model,srdf_filename,false); const size_t num_col_pairs = geom_model.collisionPairs.size(); BOOST_CHECK(num_init_col_pairs > num_col_pairs); @@ -63,7 +63,7 @@ BOOST_AUTO_TEST_CASE(readNeutralConfig) Model model; buildModel(model_filename, model); - Eigen::VectorXd q = getNeutralConfigurationFromSrdf(model,srdf_filename,false); + Eigen::VectorXd q = getNeutralConfiguration(model,srdf_filename,false); BOOST_CHECK(q.size() == model.nq); BOOST_CHECK(!q.isZero()); @@ -79,7 +79,7 @@ BOOST_AUTO_TEST_CASE(readRotorParams) Model model; buildModel(model_filename, model); - loadRotorParamsFromSrdf(model,srdf_filename,false); + loadRotorParameters(model,srdf_filename,false); BOOST_CHECK(model.rotorInertia(model.joints[model.getJointId("WAIST_P")].idx_v())==1.0); BOOST_CHECK(model.rotorGearRatio(model.joints[model.getJointId("WAIST_R")].idx_v())==1.0);