diff --git a/bindings/python/parsers/parsers.hpp b/bindings/python/parsers/parsers.hpp index 5a367a9b9d..ff20b79c41 100644 --- a/bindings/python/parsers/parsers.hpp +++ b/bindings/python/parsers/parsers.hpp @@ -193,7 +193,7 @@ namespace pinocchio static void loadReferenceConfigurationsFromXML (Model& model, const std::string & xmlStream, - const bool verbose = false) throw (std::invalid_argument) + const bool verbose = false) { std::istringstream iss (xmlStream); pinocchio::srdf::loadReferenceConfigurationsFromXML(model, iss, verbose); diff --git a/bindings/python/parsers/python.hpp b/bindings/python/parsers/python.hpp index 7a07b9062b..415110ac33 100644 --- a/bindings/python/parsers/python.hpp +++ b/bindings/python/parsers/python.hpp @@ -24,7 +24,7 @@ namespace pinocchio /// \returns The model constructed by the Python script. /// // TODO: look inside the context of Python and find an occurence of object Model - Model buildModel(const std::string & filename, const std::string & var_name = "model", bool verbose = false) throw (boost::python::error_already_set); + Model buildModel(const std::string & filename, const std::string & var_name = "model", bool verbose = false); } // namespace python diff --git a/bindings/python/parsers/python/model.cpp b/bindings/python/parsers/python/model.cpp index e1a8340837..e01a8cb464 100644 --- a/bindings/python/parsers/python/model.cpp +++ b/bindings/python/parsers/python/model.cpp @@ -21,7 +21,7 @@ namespace pinocchio { namespace bp = boost::python; - Model buildModel(const std::string & filename, const std::string & model_name, bool verbose) throw (bp::error_already_set) + Model buildModel(const std::string & filename, const std::string & model_name, bool verbose) { Py_Initialize(); diff --git a/src/parsers/srdf.hpp b/src/parsers/srdf.hpp index 5f075baccb..44b985527d 100644 --- a/src/parsers/srdf.hpp +++ b/src/parsers/srdf.hpp @@ -29,7 +29,7 @@ namespace pinocchio void removeCollisionPairs(const ModelTpl & model, GeometryModel & geomModel, const std::string & filename, - const bool verbose = false) throw (std::invalid_argument); + const bool verbose = false); /// \copydoc removeCollisionPairs template class JointCollectionTpl> @@ -37,7 +37,7 @@ namespace pinocchio void removeCollisionPairsFromSrdf(const ModelTpl & model, GeometryModel & geomModel, const std::string & filename, - const bool verbose = false) throw (std::invalid_argument) + const bool verbose = false) { removeCollisionPairs(model,geomModel,filename,verbose); } @@ -85,7 +85,7 @@ namespace pinocchio typename ModelTpl::ConfigVectorType getNeutralConfiguration(ModelTpl & model, const std::string & filename, - const bool verbose = false) throw (std::invalid_argument); + const bool verbose = false); /// \copydoc pinocchio::srdf::getNeutralConfiguration template class JointCollectionTpl> @@ -93,7 +93,7 @@ namespace pinocchio typename ModelTpl::ConfigVectorType getNeutralConfigurationFromSrdf(ModelTpl & model, const std::string & filename, - const bool verbose = false) throw (std::invalid_argument) + const bool verbose = false) { return getNeutralConfiguration(model,filename,verbose); } @@ -109,7 +109,7 @@ namespace pinocchio void loadReferenceConfigurations(ModelTpl & model, const std::string & filename, - const bool verbose = false) throw (std::invalid_argument); + const bool verbose = false); /// /// \brief Get the reference configurations of a given model associated to a SRDF file. @@ -123,7 +123,7 @@ namespace pinocchio void loadReferenceConfigurationsFromXML(ModelTpl & model, std::istream & xmlStream, - const bool verbose = false) throw (std::invalid_argument); + const bool verbose = false); /// @@ -139,14 +139,14 @@ namespace pinocchio template class JointCollectionTpl> bool loadRotorParameters(ModelTpl & model, const std::string & filename, - const bool verbose = false) throw (std::invalid_argument); + const bool verbose = false); /// \copydoc pinocchio::srdf::loadRotorParameters template class JointCollectionTpl> PINOCCHIO_DEPRECATED bool loadRotorParamsFromSrdf(ModelTpl & model, const std::string & filename, - const bool verbose = false) throw (std::invalid_argument) + const bool verbose = false) { return loadRotorParameters(model,filename,verbose); } diff --git a/src/parsers/srdf.hxx b/src/parsers/srdf.hxx index fd456ed3ba..149e428be9 100644 --- a/src/parsers/srdf.hxx +++ b/src/parsers/srdf.hxx @@ -98,7 +98,7 @@ namespace pinocchio void removeCollisionPairs(const ModelTpl & model, GeometryModel & geomModel, const std::string & filename, - const bool verbose) throw (std::invalid_argument) + const bool verbose) { // Check extension const std::string extension = filename.substr(filename.find_last_of('.')+1); @@ -134,7 +134,7 @@ namespace pinocchio template class JointCollectionTpl> bool loadRotorParameters(ModelTpl & model, const std::string & filename, - const bool verbose) throw (std::invalid_argument) + const bool verbose) { typedef ModelTpl Model; typedef typename Model::JointModel JointModel; @@ -206,7 +206,7 @@ namespace pinocchio typename ModelTpl::ConfigVectorType getNeutralConfiguration(ModelTpl & model, const std::string & filename, - const bool verbose) throw (std::invalid_argument) + const bool verbose) { typedef ModelTpl Model; typedef typename Model::JointModel JointModel; @@ -340,7 +340,7 @@ namespace pinocchio void loadReferenceConfigurations(ModelTpl & model, const std::string & filename, - const bool verbose) throw (std::invalid_argument) + const bool verbose) { // Check extension const std::string extension = filename.substr(filename.find_last_of('.')+1); @@ -365,7 +365,7 @@ namespace pinocchio void loadReferenceConfigurationsFromXML(ModelTpl & model, std::istream & xmlStream, - const bool verbose) throw (std::invalid_argument) + const bool verbose) { typedef ModelTpl Model; typedef typename Model::JointModel JointModel; diff --git a/src/parsers/urdf.hpp b/src/parsers/urdf.hpp index 5433488a4f..e6a31b3472 100644 --- a/src/parsers/urdf.hpp +++ b/src/parsers/urdf.hpp @@ -44,7 +44,7 @@ namespace pinocchio buildModel(const std::string & filename, const typename ModelTpl::JointModel & rootJoint, ModelTpl & model, - const bool verbose = false) throw (std::invalid_argument); + const bool verbose = false); /// @@ -59,7 +59,7 @@ namespace pinocchio ModelTpl & buildModel(const std::string & filename, ModelTpl & model, - const bool verbose = false) throw (std::invalid_argument); + const bool verbose = false); /// /// \brief Build the model from a URDF model with a particular joint as root of the model tree inside @@ -113,8 +113,7 @@ namespace pinocchio buildModelFromXML(const std::string & xmlStream, const JointModelVariant & rootJoint, ModelTpl & model, - const bool verbose = false) - throw (std::invalid_argument); + const bool verbose = false); /// /// \brief Build the model from an XML stream @@ -130,8 +129,7 @@ namespace pinocchio ModelTpl & buildModelFromXML(const std::string & xmlStream, ModelTpl & model, - const bool verbose = false) - throw (std::invalid_argument); + const bool verbose = false); /** @@ -161,8 +159,7 @@ namespace pinocchio const GeometryType type, GeometryModel & geomModel, const std::vector & packageDirs = std::vector (), - ::hpp::fcl::MeshLoaderPtr meshLoader = ::hpp::fcl::MeshLoaderPtr()) - throw (std::invalid_argument); + ::hpp::fcl::MeshLoaderPtr meshLoader = ::hpp::fcl::MeshLoaderPtr()); /** * @brief Build The GeometryModel from a URDF file. Search for meshes @@ -191,7 +188,7 @@ namespace pinocchio GeometryModel & geomModel, const std::string & packageDir, hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr()) - throw (std::invalid_argument) + { const std::vector dirs(1,packageDir); return buildGeom(model,filename,type,geomModel,dirs,meshLoader); @@ -224,8 +221,7 @@ namespace pinocchio const GeometryType type, GeometryModel & geomModel, const std::vector & packageDirs = std::vector (), - hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr()) - throw (std::invalid_argument); + hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr()); /** * @brief Build The GeometryModel from a URDF model. Search for meshes @@ -254,7 +250,7 @@ namespace pinocchio GeometryModel & geomModel, const std::string & packageDir, hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr()) - throw (std::invalid_argument) + { const std::vector dirs(1,packageDir); return buildGeom(model,xmlStream,type,geomModel,dirs, meshLoader); diff --git a/src/parsers/urdf/geometry.hxx b/src/parsers/urdf/geometry.hxx index 88b20ef029..986a74bf94 100644 --- a/src/parsers/urdf/geometry.hxx +++ b/src/parsers/urdf/geometry.hxx @@ -306,7 +306,7 @@ namespace pinocchio ::urdf::LinkConstSharedPtr link, const ModelTpl & model, GeometryModel & geomModel, - const std::vector & package_dirs) throw (std::invalid_argument) + const std::vector & package_dirs) { #ifndef PINOCCHIO_WITH_HPP_FCL PINOCCHIO_UNUSED_VARIABLE(tree); @@ -398,7 +398,7 @@ namespace pinocchio const ModelTpl & model, GeometryModel & geomModel, const std::vector & package_dirs, - const GeometryType type) throw (std::invalid_argument) + const GeometryType type) { switch(type) @@ -430,7 +430,6 @@ namespace pinocchio GeometryModel & geomModel, const std::vector & package_dirs, ::hpp::fcl::MeshLoaderPtr meshLoader) - throw(std::invalid_argument) { std::ifstream xmlStream(filename.c_str()); if (! xmlStream.is_open()) @@ -448,7 +447,6 @@ namespace pinocchio GeometryModel & geomModel, const std::vector & package_dirs, ::hpp::fcl::MeshLoaderPtr meshLoader) - throw(std::invalid_argument) { std::string xmlStr; { diff --git a/src/parsers/urdf/model.hxx b/src/parsers/urdf/model.hxx index 41681c6e27..9b3c412eb6 100644 --- a/src/parsers/urdf/model.hxx +++ b/src/parsers/urdf/model.hxx @@ -191,7 +191,7 @@ namespace pinocchio template class JointCollectionTpl> void parseTree(::urdf::LinkConstSharedPtr link, ModelTpl & model, - bool verbose) throw (std::invalid_argument) + bool verbose) { typedef ModelTpl Model; typedef typename Model::JointCollection JointCollection; @@ -536,7 +536,7 @@ namespace pinocchio template class JointCollectionTpl> void parseRootTree(::urdf::LinkConstSharedPtr root_link, ModelTpl & model, - const bool verbose) throw (std::invalid_argument) + const bool verbose) { addFixedJointAndBody(model, 0, SE3::Identity(), "root_joint", root_link->inertial, root_link->name); @@ -560,7 +560,7 @@ namespace pinocchio void parseRootTree(::urdf::LinkConstSharedPtr root_link, ModelTpl & model, const JointModelBase & root_joint, - const bool verbose) throw (std::invalid_argument) + const bool verbose) { addJointAndBody(model,root_joint, 0,SE3::Identity(),"root_joint", @@ -613,7 +613,7 @@ namespace pinocchio const typename ModelTpl::JointModel & root_joint, ModelTpl & model, const bool verbose) - throw (std::invalid_argument) + { ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile (filename); @@ -633,7 +633,7 @@ namespace pinocchio buildModel(const std::string & filename, ModelTpl & model, const bool verbose) - throw (std::invalid_argument) + { ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename); if (urdfTree) @@ -654,7 +654,7 @@ namespace pinocchio buildModelFromXML(const std::string & xmlStream, const JointModelVariant & rootJoint, ModelTpl & model, - const bool verbose) throw (std::invalid_argument) + const bool verbose) { ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDF(xmlStream); @@ -673,7 +673,7 @@ namespace pinocchio ModelTpl & buildModelFromXML(const std::string & xmlStream, ModelTpl & model, - const bool verbose) throw (std::invalid_argument) + const bool verbose) { ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDF(xmlStream); diff --git a/src/parsers/utils.hpp b/src/parsers/utils.hpp index bd9d18cdda..5a002215e9 100644 --- a/src/parsers/utils.hpp +++ b/src/parsers/utils.hpp @@ -62,7 +62,7 @@ namespace pinocchio * @return The path to the file (can be a relative or absolute path) */ inline std::string retrieveResourcePath(const std::string & string, - const std::vector & package_dirs) throw (std::invalid_argument) + const std::vector & package_dirs) { namespace bf = boost::filesystem; diff --git a/src/serialization/archive.hpp b/src/serialization/archive.hpp index d9d0478f72..053e5d28e2 100644 --- a/src/serialization/archive.hpp +++ b/src/serialization/archive.hpp @@ -36,7 +36,7 @@ namespace pinocchio /// template inline void loadFromText(T & object, - const std::string & filename) throw (std::invalid_argument) + const std::string & filename) { std::ifstream ifs(filename.c_str()); if(ifs) @@ -63,7 +63,7 @@ namespace pinocchio /// template inline void saveToText(const T & object, - const std::string & filename) throw (std::invalid_argument) + const std::string & filename) { std::ofstream ofs(filename.c_str()); if(ofs) @@ -90,7 +90,7 @@ namespace pinocchio template inline void loadFromXML(T & object, const std::string & filename, - const std::string & tag_name) throw (std::invalid_argument) + const std::string & tag_name) { assert(!tag_name.empty()); @@ -121,7 +121,7 @@ namespace pinocchio template inline void saveToXML(const T & object, const std::string & filename, - const std::string & tag_name) throw (std::invalid_argument) + const std::string & tag_name) { assert(!tag_name.empty()); @@ -148,7 +148,7 @@ namespace pinocchio /// template inline void loadFromBinary(T & object, - const std::string & filename) throw (std::invalid_argument) + const std::string & filename) { std::ifstream ifs(filename.c_str()); if(ifs) @@ -173,7 +173,7 @@ namespace pinocchio /// template void saveToBinary(const T & object, - const std::string & filename) throw (std::invalid_argument) + const std::string & filename) { std::ofstream ofs(filename.c_str()); if(ofs) diff --git a/src/serialization/serializable.hpp b/src/serialization/serializable.hpp index 4269ad5bb9..665b983377 100644 --- a/src/serialization/serializable.hpp +++ b/src/serialization/serializable.hpp @@ -23,39 +23,39 @@ namespace pinocchio public: /// \brief Loads a Derived object from a text file. - void loadFromText(const std::string & filename) throw (std::invalid_argument) + void loadFromText(const std::string & filename) { pinocchio::serialization::loadFromText(derived(),filename); } /// \brief Saves a Derived object as a text file. - void saveToText(const std::string & filename) const throw (std::invalid_argument) + void saveToText(const std::string & filename) const { pinocchio::serialization::saveToText(derived(),filename); } /// \brief Loads a Derived object from an XML file. void loadFromXML(const std::string & filename, - const std::string & tag_name) throw (std::invalid_argument) + const std::string & tag_name) { pinocchio::serialization::loadFromXML(derived(),filename,tag_name); } /// \brief Saves a Derived object as an XML file. void saveToXML(const std::string & filename, - const std::string & tag_name) const throw (std::invalid_argument) + const std::string & tag_name) const { pinocchio::serialization::saveToXML(derived(),filename,tag_name); } /// \brief Loads a Derived object from an binary file. - void loadFromBinary(const std::string & filename) throw (std::invalid_argument) + void loadFromBinary(const std::string & filename) { pinocchio::serialization::loadFromBinary(derived(),filename); } /// \brief Saves a Derived object as an binary file. - void saveToBinary(const std::string & filename) const throw (std::invalid_argument) + void saveToBinary(const std::string & filename) const { pinocchio::serialization::saveToBinary(derived(),filename); }