5 #include "pinocchio/parsers/urdf.hpp" 8 #include <boost/python.hpp> 17 #ifdef PINOCCHIO_WITH_URDFDOM 19 Model buildModelFromUrdf(
const std::string & filename)
26 Model & buildModelFromUrdf(
const std::string & filename,
32 Model buildModelFromUrdf(
const std::string & filename,
40 Model & buildModelFromUrdf(
const std::string & filename,
82 #ifdef PINOCCHIO_WITH_URDFDOM 84 bp::def(
"buildModelFromUrdf",
85 static_cast <
Model (*) (
const std::string &,
const JointModel &)> (pinocchio::python::buildModelFromUrdf),
86 bp::args(
"urdf_filename",
"root_joint"),
87 "Parse the URDF file given in input and return a pinocchio Model starting with the given root joint." 90 bp::def(
"buildModelFromUrdf",
91 static_cast <
Model (*) (
const std::string &)> (pinocchio::python::buildModelFromUrdf),
93 "Parse the URDF file given in input and return a pinocchio Model." 96 bp::def(
"buildModelFromUrdf",
97 static_cast <
Model & (*) (
const std::string &,
Model &)> (pinocchio::python::buildModelFromUrdf),
99 "Append to a given model a URDF structure given by its filename.",
100 bp::return_internal_reference<2>()
103 bp::def(
"buildModelFromUrdf",
104 static_cast <
Model & (*) (
const std::string &,
const JointModel &,
Model &)> (pinocchio::python::buildModelFromUrdf),
105 bp::args(
"urdf_filename",
"root_joint",
"model"),
106 "Append to a given model a URDF structure given by its filename and the root joint.",
107 bp::return_internal_reference<3>()
110 bp::def(
"buildModelFromXML",
112 bp::args(
"urdf_xml_stream",
"root_joint"),
113 "Parse the URDF XML stream given in input and return a pinocchio Model starting with the given root joint." 116 bp::def(
"buildModelFromXML",
118 bp::args(
"urdf_xml_stream",
"root_joint",
"model"),
119 "Parse the URDF XML stream given in input and append it to the input model with the given interfacing joint.",
120 bp::return_internal_reference<3>()
123 bp::def(
"buildModelFromXML",
126 "Parse the URDF XML stream given in input and return a pinocchio Model." 129 bp::def(
"buildModelFromXML",
131 bp::args(
"urdf_xml_stream",
"model"),
132 "Parse the URDF XML stream given in input and append it to the input model.",
133 bp::return_internal_reference<2>()
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)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
Main pinocchio namespace.
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)
Build the model from an XML stream with a particular joint as root of the model tree inside the model...
JointModelTpl< double > JointModel
JointCollectionTpl & model