Program Listing for File urdf.hpp

Return to documentation for file (include/pinocchio/parsers/urdf.hpp)

//
// Copyright (c) 2015-2021 CNRS INRIA
// Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
//

#ifndef __pinocchio_parsers_urdf_hpp__
#define __pinocchio_parsers_urdf_hpp__

#include "pinocchio/multibody/model.hpp"
#include "pinocchio/multibody/geometry.hpp"

#ifdef PINOCCHIO_WITH_CXX11_SUPPORT
#include <memory>
#endif

// forward declaration of the unique type from urdfdom which is expose.
namespace urdf {
  class ModelInterface;
}

namespace hpp
{
  namespace fcl
  {
    class MeshLoader;
    typedef std::shared_ptr<MeshLoader> MeshLoaderPtr;
  }
}

namespace pinocchio
{
  namespace urdf
  {

    template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
    ModelTpl<Scalar,Options,JointCollectionTpl> &
    buildModel(const std::string & filename,
               const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
               ModelTpl<Scalar,Options,JointCollectionTpl> & model,
               const bool verbose = false);


    template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
    ModelTpl<Scalar,Options,JointCollectionTpl> &
    buildModel(const std::string & filename,
               ModelTpl<Scalar,Options,JointCollectionTpl> & model,
               const bool verbose = false);

    template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
    ModelTpl<Scalar,Options,JointCollectionTpl> &
    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);

    template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
    ModelTpl<Scalar,Options,JointCollectionTpl> &
    buildModel(const boost::shared_ptr< ::urdf::ModelInterface> urdfTree,
               ModelTpl<Scalar,Options,JointCollectionTpl> & model,
               const bool verbose = false);

#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 = false);

    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

    template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
    ModelTpl<Scalar,Options,JointCollectionTpl> &
    buildModelFromXML(const std::string & xml_stream,
                      const typename ModelTpl<Scalar,Options,JointCollectionTpl>::JointModel & rootJoint,
                      ModelTpl<Scalar,Options,JointCollectionTpl> & model,
                      const bool verbose = false);

    template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
    ModelTpl<Scalar,Options,JointCollectionTpl> &
    buildModelFromXML(const std::string & xml_stream,
                      ModelTpl<Scalar,Options,JointCollectionTpl> & model,
                      const bool verbose = false);


    template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
    GeometryModel & buildGeom(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
                              const std::string & filename,
                              const GeometryType type,
                              GeometryModel & geom_model,
                              const std::vector<std::string> & package_paths = std::vector<std::string> (),
                              ::hpp::fcl::MeshLoaderPtr mesh_loader = ::hpp::fcl::MeshLoaderPtr());

    template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
    GeometryModel & buildGeom(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
                              const std::string & filename,
                              const GeometryType type,
                              GeometryModel & geom_model,
                              const std::string & package_path,
                              hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())

    {
      const std::vector<std::string> dirs(1,package_path);
      return buildGeom(model,filename,type,geom_model,dirs,mesh_loader);
    }

    template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
    GeometryModel & buildGeom(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
                              const std::istream & xml_stream,
                              const GeometryType type,
                              GeometryModel & geom_model,
                              const std::vector<std::string> & package_paths = std::vector<std::string> (),
                              hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr());

    template<typename Scalar, int Options, template<typename,int> class JointCollectionTpl>
    GeometryModel & buildGeom(const ModelTpl<Scalar,Options,JointCollectionTpl> & model,
                              const std::istream & xml_stream,
                              const GeometryType type,
                              GeometryModel & geom_model,
                              const std::string & package_path,
                              hpp::fcl::MeshLoaderPtr mesh_loader = hpp::fcl::MeshLoaderPtr())

    {
      const std::vector<std::string> dirs(1,package_path);
      return buildGeom(model,xml_stream,type,geom_model,dirs,mesh_loader);
    }


  } // namespace urdf
} // namespace pinocchio

#include "pinocchio/parsers/urdf/model.hxx"
#include "pinocchio/parsers/urdf/geometry.hxx"

#endif // ifndef __pinocchio_parsers_urdf_hpp__