Skip to content

Commit c9c3cbd

Browse files
remove deprecated throw specification
1 parent 3ffa704 commit c9c3cbd

File tree

11 files changed

+46
-52
lines changed

11 files changed

+46
-52
lines changed

bindings/python/parsers/parsers.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -193,7 +193,7 @@ namespace pinocchio
193193

194194
static void loadReferenceConfigurationsFromXML (Model& model,
195195
const std::string & xmlStream,
196-
const bool verbose = false) throw (std::invalid_argument)
196+
const bool verbose = false)
197197
{
198198
std::istringstream iss (xmlStream);
199199
pinocchio::srdf::loadReferenceConfigurationsFromXML(model, iss, verbose);

bindings/python/parsers/python.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ namespace pinocchio
2424
/// \returns The model constructed by the Python script.
2525
///
2626
// TODO: look inside the context of Python and find an occurence of object Model
27-
Model buildModel(const std::string & filename, const std::string & var_name = "model", bool verbose = false) throw (boost::python::error_already_set);
27+
Model buildModel(const std::string & filename, const std::string & var_name = "model", bool verbose = false);
2828

2929
} // namespace python
3030

bindings/python/parsers/python/model.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ namespace pinocchio
2121
{
2222
namespace bp = boost::python;
2323

24-
Model buildModel(const std::string & filename, const std::string & model_name, bool verbose) throw (bp::error_already_set)
24+
Model buildModel(const std::string & filename, const std::string & model_name, bool verbose)
2525
{
2626
Py_Initialize();
2727

src/parsers/srdf.hpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -29,15 +29,15 @@ namespace pinocchio
2929
void removeCollisionPairs(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
3030
GeometryModel & geomModel,
3131
const std::string & filename,
32-
const bool verbose = false) throw (std::invalid_argument);
32+
const bool verbose = false);
3333

3434
/// \copydoc removeCollisionPairs
3535
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
3636
PINOCCHIO_DEPRECATED
3737
void removeCollisionPairsFromSrdf(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
3838
GeometryModel & geomModel,
3939
const std::string & filename,
40-
const bool verbose = false) throw (std::invalid_argument)
40+
const bool verbose = false)
4141
{
4242
removeCollisionPairs(model,geomModel,filename,verbose);
4343
}
@@ -85,15 +85,15 @@ namespace pinocchio
8585
typename ModelTpl<Scalar,Options,JointCollectionTpl>::ConfigVectorType
8686
getNeutralConfiguration(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
8787
const std::string & filename,
88-
const bool verbose = false) throw (std::invalid_argument);
88+
const bool verbose = false);
8989

9090
/// \copydoc pinocchio::srdf::getNeutralConfiguration
9191
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
9292
PINOCCHIO_DEPRECATED
9393
typename ModelTpl<Scalar,Options,JointCollectionTpl>::ConfigVectorType
9494
getNeutralConfigurationFromSrdf(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
9595
const std::string & filename,
96-
const bool verbose = false) throw (std::invalid_argument)
96+
const bool verbose = false)
9797
{ return getNeutralConfiguration(model,filename,verbose); }
9898

9999

@@ -109,7 +109,7 @@ namespace pinocchio
109109
void
110110
loadReferenceConfigurations(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
111111
const std::string & filename,
112-
const bool verbose = false) throw (std::invalid_argument);
112+
const bool verbose = false);
113113

114114
///
115115
/// \brief Get the reference configurations of a given model associated to a SRDF file.
@@ -123,7 +123,7 @@ namespace pinocchio
123123
void
124124
loadReferenceConfigurationsFromXML(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
125125
std::istream & xmlStream,
126-
const bool verbose = false) throw (std::invalid_argument);
126+
const bool verbose = false);
127127

128128

129129
///
@@ -139,14 +139,14 @@ namespace pinocchio
139139
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
140140
bool loadRotorParameters(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
141141
const std::string & filename,
142-
const bool verbose = false) throw (std::invalid_argument);
142+
const bool verbose = false);
143143

144144
/// \copydoc pinocchio::srdf::loadRotorParameters
145145
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
146146
PINOCCHIO_DEPRECATED
147147
bool loadRotorParamsFromSrdf(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
148148
const std::string & filename,
149-
const bool verbose = false) throw (std::invalid_argument)
149+
const bool verbose = false)
150150
{
151151
return loadRotorParameters(model,filename,verbose);
152152
}

src/parsers/srdf.hxx

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -98,7 +98,7 @@ namespace pinocchio
9898
void removeCollisionPairs(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
9999
GeometryModel & geomModel,
100100
const std::string & filename,
101-
const bool verbose) throw (std::invalid_argument)
101+
const bool verbose)
102102
{
103103
// Check extension
104104
const std::string extension = filename.substr(filename.find_last_of('.')+1);
@@ -134,7 +134,7 @@ namespace pinocchio
134134
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
135135
bool loadRotorParameters(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
136136
const std::string & filename,
137-
const bool verbose) throw (std::invalid_argument)
137+
const bool verbose)
138138
{
139139
typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model;
140140
typedef typename Model::JointModel JointModel;
@@ -206,7 +206,7 @@ namespace pinocchio
206206
typename ModelTpl<Scalar,Options,JointCollectionTpl>::ConfigVectorType
207207
getNeutralConfiguration(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
208208
const std::string & filename,
209-
const bool verbose) throw (std::invalid_argument)
209+
const bool verbose)
210210
{
211211
typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model;
212212
typedef typename Model::JointModel JointModel;
@@ -340,7 +340,7 @@ namespace pinocchio
340340
void
341341
loadReferenceConfigurations(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
342342
const std::string & filename,
343-
const bool verbose) throw (std::invalid_argument)
343+
const bool verbose)
344344
{
345345
// Check extension
346346
const std::string extension = filename.substr(filename.find_last_of('.')+1);
@@ -365,7 +365,7 @@ namespace pinocchio
365365
void
366366
loadReferenceConfigurationsFromXML(ModelTpl<Scalar,Options,JointCollectionTpl> & model,
367367
std::istream & xmlStream,
368-
const bool verbose) throw (std::invalid_argument)
368+
const bool verbose)
369369
{
370370
typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model;
371371
typedef typename Model::JointModel JointModel;

src/parsers/urdf.hpp

Lines changed: 8 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ namespace pinocchio
4444
buildModel(const std::string & filename,
4545
const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
4646
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
47-
const bool verbose = false) throw (std::invalid_argument);
47+
const bool verbose = false);
4848

4949

5050
///
@@ -59,7 +59,7 @@ namespace pinocchio
5959
ModelTpl<Scalar,Options,JointCollectionTpl> &
6060
buildModel(const std::string & filename,
6161
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
62-
const bool verbose = false) throw (std::invalid_argument);
62+
const bool verbose = false);
6363

6464
///
6565
/// \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
113113
buildModelFromXML(const std::string & xmlStream,
114114
const JointModelVariant & rootJoint,
115115
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
116-
const bool verbose = false)
117-
throw (std::invalid_argument);
116+
const bool verbose = false);
118117

119118
///
120119
/// \brief Build the model from an XML stream
@@ -130,8 +129,7 @@ namespace pinocchio
130129
ModelTpl<Scalar,Options,JointCollectionTpl> &
131130
buildModelFromXML(const std::string & xmlStream,
132131
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
133-
const bool verbose = false)
134-
throw (std::invalid_argument);
132+
const bool verbose = false);
135133

136134

137135
/**
@@ -161,8 +159,7 @@ namespace pinocchio
161159
const GeometryType type,
162160
GeometryModel & geomModel,
163161
const std::vector<std::string> & packageDirs = std::vector<std::string> (),
164-
::hpp::fcl::MeshLoaderPtr meshLoader = ::hpp::fcl::MeshLoaderPtr())
165-
throw (std::invalid_argument);
162+
::hpp::fcl::MeshLoaderPtr meshLoader = ::hpp::fcl::MeshLoaderPtr());
166163

167164
/**
168165
* @brief Build The GeometryModel from a URDF file. Search for meshes
@@ -191,7 +188,7 @@ namespace pinocchio
191188
GeometryModel & geomModel,
192189
const std::string & packageDir,
193190
hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
194-
throw (std::invalid_argument)
191+
195192
{
196193
const std::vector<std::string> dirs(1,packageDir);
197194
return buildGeom(model,filename,type,geomModel,dirs,meshLoader);
@@ -224,8 +221,7 @@ namespace pinocchio
224221
const GeometryType type,
225222
GeometryModel & geomModel,
226223
const std::vector<std::string> & packageDirs = std::vector<std::string> (),
227-
hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
228-
throw (std::invalid_argument);
224+
hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr());
229225

230226
/**
231227
* @brief Build The GeometryModel from a URDF model. Search for meshes
@@ -254,7 +250,7 @@ namespace pinocchio
254250
GeometryModel & geomModel,
255251
const std::string & packageDir,
256252
hpp::fcl::MeshLoaderPtr meshLoader = hpp::fcl::MeshLoaderPtr())
257-
throw (std::invalid_argument)
253+
258254
{
259255
const std::vector<std::string> dirs(1,packageDir);
260256
return buildGeom(model,xmlStream,type,geomModel,dirs, meshLoader);

src/parsers/urdf/geometry.hxx

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -306,7 +306,7 @@ namespace pinocchio
306306
::urdf::LinkConstSharedPtr link,
307307
const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
308308
GeometryModel & geomModel,
309-
const std::vector<std::string> & package_dirs) throw (std::invalid_argument)
309+
const std::vector<std::string> & package_dirs)
310310
{
311311
#ifndef PINOCCHIO_WITH_HPP_FCL
312312
PINOCCHIO_UNUSED_VARIABLE(tree);
@@ -398,7 +398,7 @@ namespace pinocchio
398398
const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
399399
GeometryModel & geomModel,
400400
const std::vector<std::string> & package_dirs,
401-
const GeometryType type) throw (std::invalid_argument)
401+
const GeometryType type)
402402
{
403403

404404
switch(type)
@@ -430,7 +430,6 @@ namespace pinocchio
430430
GeometryModel & geomModel,
431431
const std::vector<std::string> & package_dirs,
432432
::hpp::fcl::MeshLoaderPtr meshLoader)
433-
throw(std::invalid_argument)
434433
{
435434
std::ifstream xmlStream(filename.c_str());
436435
if (! xmlStream.is_open())
@@ -448,7 +447,6 @@ namespace pinocchio
448447
GeometryModel & geomModel,
449448
const std::vector<std::string> & package_dirs,
450449
::hpp::fcl::MeshLoaderPtr meshLoader)
451-
throw(std::invalid_argument)
452450
{
453451
std::string xmlStr;
454452
{

src/parsers/urdf/model.hxx

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -191,7 +191,7 @@ namespace pinocchio
191191
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
192192
void parseTree(::urdf::LinkConstSharedPtr link,
193193
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
194-
bool verbose) throw (std::invalid_argument)
194+
bool verbose)
195195
{
196196
typedef ModelTpl<Scalar,Options,JointCollectionTpl> Model;
197197
typedef typename Model::JointCollection JointCollection;
@@ -536,7 +536,7 @@ namespace pinocchio
536536
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
537537
void parseRootTree(::urdf::LinkConstSharedPtr root_link,
538538
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
539-
const bool verbose) throw (std::invalid_argument)
539+
const bool verbose)
540540
{
541541
addFixedJointAndBody(model, 0, SE3::Identity(), "root_joint",
542542
root_link->inertial, root_link->name);
@@ -560,7 +560,7 @@ namespace pinocchio
560560
void parseRootTree(::urdf::LinkConstSharedPtr root_link,
561561
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
562562
const JointModelBase<JointModel> & root_joint,
563-
const bool verbose) throw (std::invalid_argument)
563+
const bool verbose)
564564
{
565565
addJointAndBody(model,root_joint,
566566
0,SE3::Identity(),"root_joint",
@@ -613,7 +613,7 @@ namespace pinocchio
613613
const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & root_joint,
614614
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
615615
const bool verbose)
616-
throw (std::invalid_argument)
616+
617617
{
618618
::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile (filename);
619619

@@ -633,7 +633,7 @@ namespace pinocchio
633633
buildModel(const std::string & filename,
634634
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
635635
const bool verbose)
636-
throw (std::invalid_argument)
636+
637637
{
638638
::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename);
639639
if (urdfTree)
@@ -654,7 +654,7 @@ namespace pinocchio
654654
buildModelFromXML(const std::string & xmlStream,
655655
const JointModelVariant & rootJoint,
656656
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
657-
const bool verbose) throw (std::invalid_argument)
657+
const bool verbose)
658658
{
659659
::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDF(xmlStream);
660660

@@ -673,7 +673,7 @@ namespace pinocchio
673673
ModelTpl<Scalar,Options,JointCollectionTpl> &
674674
buildModelFromXML(const std::string & xmlStream,
675675
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
676-
const bool verbose) throw (std::invalid_argument)
676+
const bool verbose)
677677
{
678678
::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDF(xmlStream);
679679

src/parsers/utils.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,7 @@ namespace pinocchio
6262
* @return The path to the file (can be a relative or absolute path)
6363
*/
6464
inline std::string retrieveResourcePath(const std::string & string,
65-
const std::vector<std::string> & package_dirs) throw (std::invalid_argument)
65+
const std::vector<std::string> & package_dirs)
6666
{
6767

6868
namespace bf = boost::filesystem;

src/serialization/archive.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ namespace pinocchio
3636
///
3737
template<typename T>
3838
inline void loadFromText(T & object,
39-
const std::string & filename) throw (std::invalid_argument)
39+
const std::string & filename)
4040
{
4141
std::ifstream ifs(filename.c_str());
4242
if(ifs)
@@ -63,7 +63,7 @@ namespace pinocchio
6363
///
6464
template<typename T>
6565
inline void saveToText(const T & object,
66-
const std::string & filename) throw (std::invalid_argument)
66+
const std::string & filename)
6767
{
6868
std::ofstream ofs(filename.c_str());
6969
if(ofs)
@@ -90,7 +90,7 @@ namespace pinocchio
9090
template<typename T>
9191
inline void loadFromXML(T & object,
9292
const std::string & filename,
93-
const std::string & tag_name) throw (std::invalid_argument)
93+
const std::string & tag_name)
9494
{
9595
assert(!tag_name.empty());
9696

@@ -121,7 +121,7 @@ namespace pinocchio
121121
template<typename T>
122122
inline void saveToXML(const T & object,
123123
const std::string & filename,
124-
const std::string & tag_name) throw (std::invalid_argument)
124+
const std::string & tag_name)
125125
{
126126
assert(!tag_name.empty());
127127

@@ -148,7 +148,7 @@ namespace pinocchio
148148
///
149149
template<typename T>
150150
inline void loadFromBinary(T & object,
151-
const std::string & filename) throw (std::invalid_argument)
151+
const std::string & filename)
152152
{
153153
std::ifstream ifs(filename.c_str());
154154
if(ifs)
@@ -173,7 +173,7 @@ namespace pinocchio
173173
///
174174
template<typename T>
175175
void saveToBinary(const T & object,
176-
const std::string & filename) throw (std::invalid_argument)
176+
const std::string & filename)
177177
{
178178
std::ofstream ofs(filename.c_str());
179179
if(ofs)

0 commit comments

Comments
 (0)