Skip to content
Snippets Groups Projects
Commit 2ce229cb authored by Nicolas Mansard's avatar Nicolas Mansard Committed by Nicolas Mansard
Browse files

[C++] Changed the signature of urdf::buildModel, that now takes the model as...

[C++] Changed the signature of urdf::buildModel, that now takes the model as input. Previous signature is kept as deprecated.
parent 21aba98a
No related branches found
No related tags found
No related merge requests found
......@@ -20,6 +20,7 @@
#define __se3_parsers_urdf_hpp__
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/deprecated.hh"
#ifdef WITH_HPP_FCL
#include "pinocchio/multibody/geometry.hpp"
#include <hpp/fcl/collision_object.h>
......@@ -47,6 +48,21 @@ namespace se3
namespace urdf
{
///
/// \brief Build the model from a URDF file with a particular joint as root of the model tree inside
/// the model given as reference argument.
///
/// \param[in] filemane The URDF complete file path.
/// \param[in] root_joint The joint at the root of the model tree.
/// \param[in] verbose Print parsing info.
/// \param[out] model Reference model where to put the parsed information.
/// \return Return the reference on argument model for convenience.
///
Model& buildModel (const std::string & filename,
const JointModelVariant & root_joint,
Model & model,
const bool verbose = false) throw (std::invalid_argument);
///
/// \brief Build the model from a URDF file with a particular joint as root of the model tree.
///
......@@ -56,10 +72,25 @@ namespace se3
///
/// \return The se3::Model of the URDF file.
///
Model buildModel (const std::string & filename,
const JointModelVariant & root_joint,
const bool verbose = false) throw (std::invalid_argument);
PINOCCHIO_DEPRECATED
inline Model buildModel (const std::string & filename,
const JointModelVariant & root_joint,
const bool verbose = false)
throw (std::invalid_argument)
{ Model m; return buildModel(filename,root_joint,m,verbose); }
///
/// \brief Build the model from a URDF file with a fixed joint as root of the model tree.
///
/// \param[in] filemane The URDF complete file path.
/// \param[in] verbose Print parsing info.
/// \param[out] model Reference model where to put the parsed information.
/// \return Return the reference on argument model for convenience.
///
Model & buildModel (const std::string & filename,
Model & model,
const bool verbose = false) throw (std::invalid_argument);
///
/// \brief Build the model from a URDF file with a fixed joint as root of the model tree.
///
......@@ -68,8 +99,11 @@ namespace se3
///
/// \return The se3::Model of the URDF file.
///
Model buildModel (const std::string & filename,
const bool verbose = false) throw (std::invalid_argument);
PINOCCHIO_DEPRECATED
inline Model buildModel (const std::string & filename,
const bool verbose = false)
throw (std::invalid_argument)
{ Model m; return buildModel(filename,m,verbose); }
#ifdef WITH_HPP_FCL
......@@ -85,15 +119,41 @@ namespace se3
* where to search for models and meshes, typically
* obtained from calling se3::rosPaths()
*
* @param[in] type The type of objects that must be loaded (must be VISUAL or COLLISION)
* @param[out] geomModel Reference where to put the parsed information.
*
* @return Returns the reference on geom model for convenience.
*
*/
GeometryModel& buildGeom(const Model & model,
const std::string & filename,
const GeometryType type,
GeometryModel & geomModel,
const std::vector<std::string> & package_dirs = std::vector<std::string> ())
throw (std::invalid_argument);
/**
* @brief Inline call to the previous method (deprecated).
*
* @param[in] model The model of the robot, built with
* urdf::buildModel
* @param[in] filename The URDF complete (absolute) file path
* @param[in] package_dirs A vector containing the different directories
* where to search for models and meshes, typically
* obtained from calling se3::rosPaths()
*
*@param[in] type The type of objects that must be loaded ( can be VISUAL or COLLISION, or NONE)
*
* @return The GeometryModel associated to the urdf file and the given Model.
*
*/
GeometryModel buildGeom(const Model & model,
const std::string & filename,
const std::vector<std::string> & package_dirs = std::vector<std::string> (),
const GeometryType type = NONE) throw (std::invalid_argument);
PINOCCHIO_DEPRECATED
inline GeometryModel buildGeom(const Model & model,
const std::string & filename,
const std::vector<std::string> & package_dirs = std::vector<std::string> (),
const GeometryType type = NONE)
throw (std::invalid_argument)
{ GeometryModel g; return buildGeom (model,filename,type,g,package_dirs); }
#endif
......
......@@ -249,10 +249,12 @@ namespace se3
GeometryModel buildGeom(const Model & model,
const std::string & filename,
const std::vector<std::string> & package_dirs,
const GeometryType type) throw(std::invalid_argument)
GeometryModel& buildGeom(const Model & model,
const std::string & filename,
const GeometryType type,
GeometryModel & model_geom,
const std::vector<std::string> & package_dirs)
throw(std::invalid_argument)
{
if (type == NONE)
{
......@@ -260,8 +262,6 @@ namespace se3
throw std::invalid_argument(exception_message);
}
GeometryModel model_geom;
std::vector<std::string> hint_directories(package_dirs);
// Append the ROS_PACKAGE_PATH
......
......@@ -596,10 +596,12 @@ namespace se3
}
}; // struct ParseRootTreeVisitor
Model buildModel(const std::string & filename, const JointModelVariant & root_joint, const bool verbose) throw (std::invalid_argument)
Model& buildModel(const std::string & filename,
const JointModelVariant & root_joint,
Model & model,
const bool verbose)
throw (std::invalid_argument)
{
Model model;
::urdf::ModelInterfacePtr urdfTree = ::urdf::parseURDFFile (filename);
if (urdfTree)
ParseRootTreeVisitor::run(urdfTree->getRoot(),model,root_joint,verbose);
......@@ -608,14 +610,12 @@ namespace se3
const std::string exception_message ("The file " + filename + " does not contain a valid URDF model.");
throw std::invalid_argument(exception_message);
}
return model;
}
Model buildModel(const std::string & filename, const bool verbose) throw (std::invalid_argument)
Model& buildModel(const std::string & filename, Model& model,const bool verbose)
throw (std::invalid_argument)
{
Model model;
::urdf::ModelInterfacePtr urdfTree = ::urdf::parseURDFFile (filename);
if (urdfTree)
details::parseRootTree(urdfTree->getRoot(),model,verbose);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment