Skip to content

Commit

Permalink
Switching to use ModelLoader in all the codebase
Browse files Browse the repository at this point in the history
We should use the C++14 [[deprecated]] attributes.
Unfortunately they have some issues with SWIG, see robotology#461

Using IDYNTREE_DEPRECATED for now
  • Loading branch information
francesco-romano committed Jul 31, 2018
1 parent 8676f69 commit 0dcb1a8
Show file tree
Hide file tree
Showing 17 changed files with 119 additions and 173 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -107,26 +107,28 @@ class ExtWrenchesAndJointTorquesEstimator
/**
* Load model and sensors from file.
*
* @deprecated Use iDynTree::ModelLoader::loadModelFromFile and call setModelAndSensors
* on the parsed Model and SensorsList
*
* @param[in] filename path to the file to load.
* @param[in] filetype (optional) explicit definiton of the filetype to load.
* Only "urdf" is supported at the moment.
* @return true if all went well (files were correctly loaded and consistent), false otherwise.
*
*/
IDYNTREE_DEPRECATED_WITH_MSG("Use iDynTree::ModelLoader::loadModelFromFile and call setModelAndSensors on the parsed Model and SensorsList")
bool loadModelAndSensorsFromFile(const std::string filename, const std::string filetype="");

/**
* Load model and sensors from file, specifieng the dof considered for the estimation.
*
* @note this will create e a reduced model only with the joint specified in consideredDOFs and the
* fixed joints in which FT sensor are mounted.
*
* @param[in] filename path to the file to load.
* @param[in] consideredDOFs list of dof to consider in the model.
* @param[in] filetype (optional) explicit definiton of the filetype to load.
* Only "urdf" is supported at the moment.
* @return true if all went well (files were correctly loaded and consistent), false otherwise.
*
*
* \note this will create e a reduced model only with the joint specified in consideredDOFs and the
* fixed joints in which FT sensor are mounted.
*/
bool loadModelAndSensorsFromFileWithSpecifiedDOFs(const std::string filename,
const std::vector<std::string> & consideredDOFs,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -121,26 +121,31 @@ class SimpleLeggedOdometry
/**
* Load model from file.
*
* @deprecated Use iDynTree::ModelLoader::loadModelFromFile and call setModel on the parsed Model
*
* @param[in] filename path to the file to load.
* @param[in] filetype (optional) explicit definiton of the filetype to load.
* Only "urdf" is supported at the moment.
* @return true if all went well (files were correctly loaded and consistent), false otherwise.
*
*/
IDYNTREE_DEPRECATED_WITH_MSG("Use iDynTree::ModelLoader::loadModelFromFile and call setModel on the parsed Model")
bool loadModelFromFile(const std::string filename, const std::string filetype="");

/**
* Load model from file, specifieng the dof considered for the estimation.
*
* @deprecated Use iDynTree::ModelLoader::loadReducedModelFromFile and call setModel on the parsed Model
*
* @note this will create e a reduced model only with the joint specified in consideredDOFs
*
* @param[in] filename path to the file to load.
* @param[in] consideredDOFs list of dof to consider in the model.
* @param[in] filetype (optional) explicit definiton of the filetype to load.
* Only "urdf" is supported at the moment.
* @return true if all went well (files were correctly loaded and consistent), false otherwise.
*
*
* \note this will create e a reduced model only with the joint specified in consideredDOFs
*/
IDYNTREE_DEPRECATED_WITH_MSG("Use iDynTree::ModelLoader::loadReducedModelFromFile and call setModel on the parsed Model")
bool loadModelFromFileWithSpecifiedDOFs(const std::string filename,
const std::vector<std::string> & consideredDOFs,
const std::string filetype="");
Expand Down
67 changes: 19 additions & 48 deletions src/estimation/src/ExtWrenchesAndJointTorquesEstimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,7 @@
#include <iDynTree/Sensors/SixAxisFTSensor.h>
#include <iDynTree/Sensors/PredictSensorsMeasurements.h>

#include <iDynTree/ModelIO/URDFModelImport.h>
#include <iDynTree/ModelIO/URDFGenericSensorsImport.h>
#include <iDynTree/ModelIO/ModelLoader.h>

#include <iDynTree/Core/EigenHelpers.h>

Expand Down Expand Up @@ -119,56 +118,28 @@ bool ExtWrenchesAndJointTorquesEstimator::setModelAndSensors(const Model& _model
}

bool ExtWrenchesAndJointTorquesEstimator::loadModelAndSensorsFromFile(const std::string filename,
const std::string /*filetype*/)
const std::string filetype)
{
Model _model;
SensorsList _sensors;

bool parsingCorrect = false;

parsingCorrect = modelFromURDF(filename,_model);

if( !parsingCorrect )
{
reportError("ExtWrenchesAndJointTorquesEstimator","loadModelAndSensorsFromFile","Error in parsing model from URDF.");
return false;
}

parsingCorrect = sensorsFromURDF(filename,_model,_sensors);

if( !parsingCorrect )
{
reportError("ExtWrenchesAndJointTorquesEstimator","loadModelAndSensorsFromFile","Error in parsing sensors from URDF.");
ModelLoader loader;
if (!loader.loadModelFromFile(filename, filetype)) {
reportError("ExtWrenchesAndJointTorquesEstimator", "loadModelAndSensorsFromFile", "Error in parsing from URDF.");
return false;
}

return setModelAndSensors(_model,_sensors);
return setModelAndSensors(loader.model(), loader.sensors());
}

bool ExtWrenchesAndJointTorquesEstimator::loadModelAndSensorsFromFileWithSpecifiedDOFs(const std::string filename,
const std::vector< std::string >& consideredDOFs,
const std::string /*filetype*/)
const std::string filetype)
{
Model _modelFull;
SensorsList _sensorsFull;

bool parsingCorrect = false;

parsingCorrect = modelFromURDF(filename,_modelFull);

if( !parsingCorrect )
{
reportError("ExtWrenchesAndJointTorquesEstimator","loadModelAndSensorsFromFileWithSpecifiedDOFs","Error in parsing model from URDF.");
ModelLoader loader;
if (!loader.loadModelFromFile(filename, filetype)) {
reportError("ExtWrenchesAndJointTorquesEstimator", "loadModelAndSensorsFromFileWithSpecifiedDOFs", "Error in parsing from URDF.");
return false;
}

parsingCorrect = sensorsFromURDF(filename,_modelFull,_sensorsFull);

if( !parsingCorrect )
{
reportError("ExtWrenchesAndJointTorquesEstimator","loadModelAndSensorsFromFileWithSpecifiedDOFs","Error in parsing sensors from URDF.");
return false;
}
Model _modelFull = loader.model();
SensorsList _sensorsFull = loader.sensors();

// We need to create a reduced model, inclusing only the consideredDOFs and the joints used by the FT sensors
std::vector< std::string > consideredJoints = consideredDOFs;
Expand All @@ -177,22 +148,22 @@ bool ExtWrenchesAndJointTorquesEstimator::loadModelAndSensorsFromFileWithSpecifi
std::vector< std::string > ftJointNames;
getFTJointNames(_sensorsFull,ftJointNames);

for(size_t i=0; i < ftJointNames.size(); i++)
for (size_t i = 0; i < ftJointNames.size(); i++)
{
// Only add an F/T sensor joint if it is not already in consideredDOFs
if( std::find(consideredJoints.begin(),consideredJoints.end(),ftJointNames[i]) == consideredJoints.end() )
{
consideredJoints.push_back(ftJointNames[i]);
}
if (std::find(consideredJoints.begin(), consideredJoints.end(), ftJointNames[i]) == consideredJoints.end())
{
consideredJoints.push_back(ftJointNames[i]);
}
}


Model _modelReduced;
SensorsList _sensorsReduced;

parsingCorrect = createReducedModelAndSensors(_modelFull,_sensorsFull,consideredJoints,_modelReduced,_sensorsReduced);
bool parsingCorrect = createReducedModelAndSensors(_modelFull,_sensorsFull,consideredJoints,_modelReduced,_sensorsReduced);

if( !parsingCorrect )
if (!parsingCorrect)
{
reportError("ExtWrenchesAndJointTorquesEstimator","loadModelAndSensorsFromFileWithSpecifiedDOFs","Error in creating reduced model and sensors.");
return false;
Expand Down
41 changes: 10 additions & 31 deletions src/estimation/src/SimpleLeggedOdometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,7 @@
#include <iDynTree/Model/Indices.h>
#include <iDynTree/Model/ModelTransformers.h>

#include <iDynTree/ModelIO/URDFModelImport.h>
#include <iDynTree/ModelIO/URDFGenericSensorsImport.h>
#include <iDynTree/ModelIO/ModelLoader.h>

#include <sstream>

Expand Down Expand Up @@ -185,50 +184,30 @@ bool SimpleLeggedOdometry::setModel(const Model& _model)


bool SimpleLeggedOdometry::loadModelFromFile(const std::string filename,
const std::string /*filetype*/)
const std::string filetype)
{
Model _model;

bool parsingCorrect = false;

parsingCorrect = modelFromURDF(filename,_model);

if( !parsingCorrect )
{
ModelLoader loader;
if (!loader.loadModelFromFile(filename, filetype)) {
reportError("SimpleLeggedOdometry",
"loadModelFromFile",
"Error in parsing model from URDF.");
return false;
}

return setModel(_model);
return setModel(loader.model());
}

bool SimpleLeggedOdometry::loadModelFromFileWithSpecifiedDOFs(const std::string filename,
const std::vector< std::string >& consideredDOFs,
const std::string /*filetype*/)
const std::vector<std::string>& consideredDOFs,
const std::string filetype)
{
Model _modelFull;

bool parsingCorrect = false;

parsingCorrect = modelFromURDF(filename,_modelFull);

if( !parsingCorrect )
{
ModelLoader loader;
if (!loader.loadReducedModelFromFile(filename, consideredDOFs, filetype)) {
reportError("SimpleLeggedOdometry",
"loadModelFromFileWithSpecifiedDOFs",
"Error in parsing model from URDF.");
return false;
}


Model _modelReduced;

// Create a reduced model: this will lump all not considered joints
iDynTree::createReducedModel(_modelFull,consideredDOFs,_modelReduced);

return setModel(_modelReduced);
return setModel(loader.model());
}


Expand Down
4 changes: 4 additions & 0 deletions src/high-level/include/iDynTree/KinDynComputations.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@

#include <iDynTree/Core/VectorFixSize.h>
#include <iDynTree/Core/MatrixDynSize.h>
#include <iDynTree/Core/Utils.h>


#include <iDynTree/Model/Indices.h>
#include <iDynTree/Model/FreeFloatingMatrices.h>
Expand Down Expand Up @@ -124,6 +126,7 @@ class KinDynComputations {
* @param filetype type of the file to load, currently supporting only urdf type.
*
*/
IDYNTREE_DEPRECATED_WITH_MSG("Use iDynTree::ModelLoader::loadRobotModelFromFile and pass the Model to loadRobotModel")
bool loadRobotModelFromFile(const std::string & filename, const std::string & filetype="urdf");

/**
Expand All @@ -133,6 +136,7 @@ class KinDynComputations {
* @param filetype type of the file to load, currently supporting only urdf type.
*
*/
IDYNTREE_DEPRECATED_WITH_MSG("Use iDynTree::ModelLoader::loadRobotModelFromString and pass the Model to loadRobotModel")
bool loadRobotModelFromString(const std::string & modelString, const std::string & filetype="urdf");

/**
Expand Down
44 changes: 9 additions & 35 deletions src/high-level/src/KinDynComputations.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
#include <iDynTree/Model/Dynamics.h>
#include <iDynTree/Model/Jacobians.h>

#include <iDynTree/ModelIO/URDFModelImport.h>
#include <iDynTree/ModelIO/ModelLoader.h>

#include <cassert>
#include <iostream>
Expand Down Expand Up @@ -333,49 +333,23 @@ void KinDynComputations::computeBiasAccFwdKinematics()
bool KinDynComputations::loadRobotModelFromFile(const std::string& filename,
const std::string& filetype)
{
if( filetype != "urdf" )
{
std::cerr << "[ERROR] unknown format " << filetype <<
" . Currently only the urdf format is supported." << std::endl;
ModelLoader loader;
if (!loader.loadModelFromFile(filename, filetype)) {
reportError("KinDynComputations", "loadRobotModelFromFile", "Error in loading robot model");
return false;
}

std::ifstream ifs(filename.c_str());

if( !ifs )
{
std::cerr << "[ERROR] impossible to open file " << filename << std::endl;
return false;
}

std::string model_string( (std::istreambuf_iterator<char>(ifs) ),
(std::istreambuf_iterator<char>() ) );

return this->loadRobotModelFromString(model_string);
return this->loadRobotModel(loader.model());
}

bool KinDynComputations::loadRobotModelFromString(const std::string& modelString,
const std::string& filetype)
{
if( filetype != "urdf" )
{
std::cerr << "[ERROR] unknown format " << filetype <<
" . Currently only the urdf format is supported." << std::endl;
ModelLoader loader;
if (!loader.loadModelFromString(modelString, filetype)) {
reportError("KinDynComputations", "loadRobotModelFromString", "Error in loading robot model");
return false;
}

Model model;
bool ok = modelFromURDFString(modelString,model);

if( !ok )
{
std::cerr << "[ERROR] error in loading robot model" << std::endl;
return false;
}
else
{
return this->loadRobotModel(model);
}
return this->loadRobotModel(loader.model());
}

bool KinDynComputations::loadRobotModel(const Model& model)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@

#include <string>

#include <iDynTree/Core/Utils.h>

#ifdef __DEPRECATED
#warning <iDynTree/ModelIO/URDFGenericSensorsImport.h> is deprecated. Please use <iDynTree/ModelIO/ModelLoader.h> and the classes contained in it. To disable this warning use -Wno-deprecated.
#endif
Expand All @@ -34,7 +36,7 @@ class Model;
* @return true if all went ok, false otherwise.
* @deprecated Please use iDynTree::ModelLoader::loadModelFromFile to load a iDynTree::SensorsList from a URDF file.
*/
[[deprecated("Please use iDynTree::ModelLoader::loadModelFromFile to load a iDynTree::SensorsList from a URDF file.")]]
IDYNTREE_DEPRECATED_WITH_MSG("Please use iDynTree::ModelLoader::loadModelFromFile to load a iDynTree::SensorsList from a URDF file.")
bool sensorsFromURDF(const std::string & urdf_filename,
iDynTree::SensorsList & output);

Expand All @@ -49,7 +51,7 @@ bool sensorsFromURDF(const std::string & urdf_filename,
* @return true if all went ok, false otherwise.
* @deprecated Please use iDynTree::ModelLoader::loadModelFromFile to load a iDynTree::SensorsList from a URDF file.
*/
[[deprecated("Please use iDynTree::ModelLoader::loadModelFromFile to load a iDynTree::SensorsList from a URDF file.")]]
IDYNTREE_DEPRECATED_WITH_MSG("Please use iDynTree::ModelLoader::loadModelFromFile to load a iDynTree::SensorsList from a URDF file.")
bool sensorsFromURDF(const std::string & urdf_filename,
const Model & model,
iDynTree::SensorsList & output);
Expand All @@ -63,7 +65,7 @@ bool sensorsFromURDF(const std::string & urdf_filename,
* @return true if all went ok, false otherwise.
* @deprecated Please use iDynTree::ModelLoader::loadModelFromString to load a iDynTree::SensorsList from a URDF string.
*/
[[deprecated("Please use iDynTree::ModelLoader::loadModelFromString to load a iDynTree::SensorsList from a URDF string.")]]
IDYNTREE_DEPRECATED_WITH_MSG("Please use iDynTree::ModelLoader::loadModelFromString to load a iDynTree::SensorsList from a URDF string.")
bool sensorsFromURDFString(const std::string & urdf_string,
iDynTree::SensorsList & output);

Expand All @@ -77,7 +79,7 @@ bool sensorsFromURDFString(const std::string & urdf_string,
* @return true if all went ok, false otherwise.
* @deprecated Please use iDynTree::ModelLoader::loadModelFromString to load a iDynTree::SensorsList from a URDF string.
*/
[[deprecated("Please use iDynTree::ModelLoader::loadModelFromString to load a iDynTree::SensorsList from a URDF string.")]]
IDYNTREE_DEPRECATED_WITH_MSG("Please use iDynTree::ModelLoader::loadModelFromString to load a iDynTree::SensorsList from a URDF string.")
bool sensorsFromURDFString(const std::string & urdf_string,
const Model & model,
iDynTree::SensorsList & output);
Expand Down
Loading

0 comments on commit 0dcb1a8

Please sign in to comment.