Skip to content
Snippets Groups Projects
Commit c5d48775 authored by Joseph Mirabel's avatar Joseph Mirabel
Browse files

[URDF] Enforce backward compatibility.

parent d316c390
No related branches found
No related tags found
No related merge requests found
......@@ -9,9 +9,12 @@
#include "pinocchio/multibody/model.hpp"
#include "pinocchio/multibody/geometry.hpp"
#ifdef PINOCCHIO_WITH_CXX11_SUPPORT
#include <memory>
#endif
/// \cond
// forward declaration of the unique type from urdfdom which is expose (mostly
// for backward compatibility).
// forward declaration of the unique type from urdfdom which is expose.
namespace urdf {
class ModelInterface;
}
......@@ -77,7 +80,7 @@ namespace pinocchio
/// or ::urdf::parseURDFFile
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl> &
buildModel(const ::urdf::ModelInterface* urdfTree,
buildModel(const boost::shared_ptr<::urdf::ModelInterface> urdfTree,
const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose = false);
......@@ -94,10 +97,27 @@ namespace pinocchio
/// or ::urdf::parseURDFFile
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl> &
buildModel(const ::urdf::ModelInterface* urdfTree,
buildModel(const boost::shared_ptr<::urdf::ModelInterface> urdfTree,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose = false);
#ifdef PINOCCHIO_WITH_CXX11_SUPPORT
/// copydoc buildModel<Scalar,Options,JointCollectionTpl>(const boost::shared_ptr<::urdf::ModelInterface>, const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel &, ModelTpl<Scalar,Options,JointCollectionTpl> &, const bool verbose)
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl> &
buildModel(const std::shared_ptr<::urdf::ModelInterface> urdfTree,
const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose = false);
/// copydoc buildModel<Scalar,Options,JointCollectionTpl>(const boost::shared_ptr<::urdf::ModelInterface>, ModelTpl<Scalar,Options,JointCollectionTpl> &, const bool verbose)
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl> &
buildModel(const std::shared_ptr<::urdf::ModelInterface> urdfTree,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose = false);
#endif
///
/// \brief Build the model from an XML stream with a particular joint as root of the model tree inside
/// the model given as reference argument.
......
......@@ -421,7 +421,7 @@ namespace pinocchio
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl> &
buildModel(const ::urdf::ModelInterface* urdfTree,
buildModel(const boost::shared_ptr<::urdf::ModelInterface> urdfTree,
const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose)
......@@ -429,23 +429,52 @@ namespace pinocchio
PINOCCHIO_CHECK_INPUT_ARGUMENT(urdfTree != NULL);
details::UrdfVisitorWithRootJoint<Scalar, Options, JointCollectionTpl> visitor (model, rootJoint);
if (verbose) visitor.log = &std::cout;
parseRootTree(urdfTree, visitor);
parseRootTree(urdfTree.get(), visitor);
return model;
}
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl> &
buildModel(const ::urdf::ModelInterface* urdfTree,
buildModel(const boost::shared_ptr<::urdf::ModelInterface> urdfTree,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose)
{
PINOCCHIO_CHECK_INPUT_ARGUMENT(urdfTree != NULL);
details::UrdfVisitor<Scalar, Options, JointCollectionTpl> visitor (model);
if (verbose) visitor.log = &std::cout;
parseRootTree(urdfTree, visitor);
parseRootTree(urdfTree.get(), visitor);
return model;
}
#ifdef PINOCCHIO_WITH_CXX11_SUPPORT
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl> &
buildModel(const std::shared_ptr<::urdf::ModelInterface> urdfTree,
const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose)
{
PINOCCHIO_CHECK_INPUT_ARGUMENT(urdfTree != NULL);
details::UrdfVisitorWithRootJoint<Scalar, Options, JointCollectionTpl> visitor (model, rootJoint);
if (verbose) visitor.log = &std::cout;
parseRootTree(urdfTree.get(), visitor);
return model;
}
template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
ModelTpl<Scalar,Options,JointCollectionTpl> &
buildModel(const std::shared_ptr<::urdf::ModelInterface> urdfTree,
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
const bool verbose)
{
PINOCCHIO_CHECK_INPUT_ARGUMENT(urdfTree != NULL);
details::UrdfVisitor<Scalar, Options, JointCollectionTpl> visitor (model);
if (verbose) visitor.log = &std::cout;
parseRootTree(urdfTree.get(), visitor);
return model;
}
#endif
} // namespace urdf
} // namespace pinocchio
......
......@@ -139,7 +139,7 @@ BOOST_AUTO_TEST_CASE ( build_model_from_UDRFTree )
::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename);
pinocchio::Model model;
pinocchio::urdf::buildModel(urdfTree.get(), model);
pinocchio::urdf::buildModel(urdfTree, model);
BOOST_CHECK(model.nq == 31);
}
......@@ -180,7 +180,7 @@ BOOST_AUTO_TEST_CASE ( build_model_with_joint_from_UDRFTree )
::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename);
pinocchio::Model model;
pinocchio::urdf::buildModel(urdfTree.get(), pinocchio::JointModelFreeFlyer(), model);
pinocchio::urdf::buildModel(urdfTree, pinocchio::JointModelFreeFlyer(), model);
BOOST_CHECK(model.nq == 38);
}
......
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