Skip to content

Commit

Permalink
Merge pull request #788 from christian-rauch/del_throw_spec
Browse files Browse the repository at this point in the history
remove deprecated throw specification
  • Loading branch information
jcarpent authored Apr 30, 2019
2 parents 11088b5 + c9c3cbd commit 044ea93
Show file tree
Hide file tree
Showing 11 changed files with 46 additions and 52 deletions.
2 changes: 1 addition & 1 deletion bindings/python/parsers/parsers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion bindings/python/parsers/python.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
2 changes: 1 addition & 1 deletion bindings/python/parsers/python/model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();

Expand Down
16 changes: 8 additions & 8 deletions src/parsers/srdf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,15 @@ namespace pinocchio
void removeCollisionPairs(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
GeometryModel & geomModel,
const std::string & filename,
const bool verbose = false) throw (std::invalid_argument);
const bool verbose = false);

/// \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)
{
removeCollisionPairs(model,geomModel,filename,verbose);
}
Expand Down Expand Up @@ -85,15 +85,15 @@ namespace pinocchio
typename ModelTpl<Scalar,Options,JointCollectionTpl>::ConfigVectorType
getNeutralConfiguration(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const std::string & filename,
const bool verbose = false) throw (std::invalid_argument);
const bool verbose = false);

/// \copydoc pinocchio::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)
{ return getNeutralConfiguration(model,filename,verbose); }


Expand All @@ -109,7 +109,7 @@ namespace pinocchio
void
loadReferenceConfigurations(ModelTpl<Scalar,Options,JointCollectionTpl> & 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.
Expand All @@ -123,7 +123,7 @@ namespace pinocchio
void
loadReferenceConfigurationsFromXML(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
std::istream & xmlStream,
const bool verbose = false) throw (std::invalid_argument);
const bool verbose = false);


///
Expand All @@ -139,14 +139,14 @@ namespace pinocchio
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);
const bool verbose = false);

/// \copydoc pinocchio::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 = false) throw (std::invalid_argument)
const bool verbose = false)
{
return loadRotorParameters(model,filename,verbose);
}
Expand Down
10 changes: 5 additions & 5 deletions src/parsers/srdf.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ namespace pinocchio
void removeCollisionPairs(const ModelTpl<Scalar,Options,JointCollectionTpl> & 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);
Expand Down Expand Up @@ -134,7 +134,7 @@ namespace pinocchio
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
bool loadRotorParameters(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const std::string & filename,
const bool verbose) throw (std::invalid_argument)
const bool verbose)
{
typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model;
typedef typename Model::JointModel JointModel;
Expand Down Expand Up @@ -206,7 +206,7 @@ namespace pinocchio
typename ModelTpl<Scalar,Options,JointCollectionTpl>::ConfigVectorType
getNeutralConfiguration(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const std::string & filename,
const bool verbose) throw (std::invalid_argument)
const bool verbose)
{
typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model;
typedef typename Model::JointModel JointModel;
Expand Down Expand Up @@ -340,7 +340,7 @@ namespace pinocchio
void
loadReferenceConfigurations(ModelTpl<Scalar,Options,JointCollectionTpl> & 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);
Expand All @@ -365,7 +365,7 @@ namespace pinocchio
void
loadReferenceConfigurationsFromXML(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
std::istream & xmlStream,
const bool verbose) throw (std::invalid_argument)
const bool verbose)
{
typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model;
typedef typename Model::JointModel JointModel;
Expand Down
20 changes: 8 additions & 12 deletions src/parsers/urdf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ namespace pinocchio
buildModel(const std::string & filename,
const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose = false) throw (std::invalid_argument);
const bool verbose = false);


///
Expand All @@ -59,7 +59,7 @@ namespace pinocchio
ModelTpl<Scalar,Options,JointCollectionTpl> &
buildModel(const std::string & filename,
ModelTpl<Scalar,Options,JointCollectionTpl> & 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
Expand Down Expand Up @@ -113,8 +113,7 @@ namespace pinocchio
buildModelFromXML(const std::string & xmlStream,
const JointModelVariant & rootJoint,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose = false)
throw (std::invalid_argument);
const bool verbose = false);

///
/// \brief Build the model from an XML stream
Expand All @@ -130,8 +129,7 @@ namespace pinocchio
ModelTpl<Scalar,Options,JointCollectionTpl> &
buildModelFromXML(const std::string & xmlStream,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose = false)
throw (std::invalid_argument);
const bool verbose = false);


/**
Expand Down Expand Up @@ -161,8 +159,7 @@ namespace pinocchio
const GeometryType type,
GeometryModel & geomModel,
const std::vector<std::string> & packageDirs = std::vector<std::string> (),
::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
Expand Down Expand Up @@ -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<std::string> dirs(1,packageDir);
return buildGeom(model,filename,type,geomModel,dirs,meshLoader);
Expand Down Expand Up @@ -224,8 +221,7 @@ namespace pinocchio
const GeometryType type,
GeometryModel & geomModel,
const std::vector<std::string> & packageDirs = std::vector<std::string> (),
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
Expand Down Expand Up @@ -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<std::string> dirs(1,packageDir);
return buildGeom(model,xmlStream,type,geomModel,dirs, meshLoader);
Expand Down
6 changes: 2 additions & 4 deletions src/parsers/urdf/geometry.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -306,7 +306,7 @@ namespace pinocchio
::urdf::LinkConstSharedPtr link,
const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
GeometryModel & geomModel,
const std::vector<std::string> & package_dirs) throw (std::invalid_argument)
const std::vector<std::string> & package_dirs)
{
#ifndef PINOCCHIO_WITH_HPP_FCL
PINOCCHIO_UNUSED_VARIABLE(tree);
Expand Down Expand Up @@ -398,7 +398,7 @@ namespace pinocchio
const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
GeometryModel & geomModel,
const std::vector<std::string> & package_dirs,
const GeometryType type) throw (std::invalid_argument)
const GeometryType type)
{

switch(type)
Expand Down Expand Up @@ -430,7 +430,6 @@ namespace pinocchio
GeometryModel & geomModel,
const std::vector<std::string> & package_dirs,
::hpp::fcl::MeshLoaderPtr meshLoader)
throw(std::invalid_argument)
{
std::ifstream xmlStream(filename.c_str());
if (! xmlStream.is_open())
Expand All @@ -448,7 +447,6 @@ namespace pinocchio
GeometryModel & geomModel,
const std::vector<std::string> & package_dirs,
::hpp::fcl::MeshLoaderPtr meshLoader)
throw(std::invalid_argument)
{
std::string xmlStr;
{
Expand Down
14 changes: 7 additions & 7 deletions src/parsers/urdf/model.hxx
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ namespace pinocchio
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
void parseTree(::urdf::LinkConstSharedPtr link,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
bool verbose) throw (std::invalid_argument)
bool verbose)
{
typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model;
typedef typename Model::JointCollection JointCollection;
Expand Down Expand Up @@ -536,7 +536,7 @@ namespace pinocchio
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
void parseRootTree(::urdf::LinkConstSharedPtr root_link,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose) throw (std::invalid_argument)
const bool verbose)
{
addFixedJointAndBody(model, 0, SE3::Identity(), "root_joint",
root_link->inertial, root_link->name);
Expand All @@ -560,7 +560,7 @@ namespace pinocchio
void parseRootTree(::urdf::LinkConstSharedPtr root_link,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const JointModelBase<JointModel> & root_joint,
const bool verbose) throw (std::invalid_argument)
const bool verbose)
{
addJointAndBody(model,root_joint,
0,SE3::Identity(),"root_joint",
Expand Down Expand Up @@ -613,7 +613,7 @@ namespace pinocchio
const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & root_joint,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose)
throw (std::invalid_argument)

{
::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile (filename);

Expand All @@ -633,7 +633,7 @@ namespace pinocchio
buildModel(const std::string & filename,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose)
throw (std::invalid_argument)

{
::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename);
if (urdfTree)
Expand All @@ -654,7 +654,7 @@ namespace pinocchio
buildModelFromXML(const std::string & xmlStream,
const JointModelVariant & rootJoint,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose) throw (std::invalid_argument)
const bool verbose)
{
::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDF(xmlStream);

Expand All @@ -673,7 +673,7 @@ namespace pinocchio
ModelTpl<Scalar,Options,JointCollectionTpl> &
buildModelFromXML(const std::string & xmlStream,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose) throw (std::invalid_argument)
const bool verbose)
{
::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDF(xmlStream);

Expand Down
2 changes: 1 addition & 1 deletion src/parsers/utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string> & package_dirs) throw (std::invalid_argument)
const std::vector<std::string> & package_dirs)
{

namespace bf = boost::filesystem;
Expand Down
12 changes: 6 additions & 6 deletions src/serialization/archive.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ namespace pinocchio
///
template<typename T>
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)
Expand All @@ -63,7 +63,7 @@ namespace pinocchio
///
template<typename T>
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)
Expand All @@ -90,7 +90,7 @@ namespace pinocchio
template<typename T>
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());

Expand Down Expand Up @@ -121,7 +121,7 @@ namespace pinocchio
template<typename T>
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());

Expand All @@ -148,7 +148,7 @@ namespace pinocchio
///
template<typename T>
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)
Expand All @@ -173,7 +173,7 @@ namespace pinocchio
///
template<typename T>
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)
Expand Down
Loading

0 comments on commit 044ea93

Please sign in to comment.