initParam() calls through to urdf::initParam()

This commit is contained in:
wim 2010-06-24 19:20:16 +00:00
parent 598019400c
commit 2b84aed3e5
2 changed files with 16 additions and 0 deletions

View File

@ -51,6 +51,13 @@ namespace kdl_parser{
*/ */
bool treeFromFile(const std::string& file, KDL::Tree& tree); bool treeFromFile(const std::string& file, KDL::Tree& tree);
/** Constructs a KDL tree from the parameter server, given the parameter name
* \param param the name of the parameter on the parameter server
* \param tree The resulting KDL Tree
* returns true on success, false on failure
*/
bool treeFromParam(const std::string& param, KDL::Tree& tree);
/** Constructs a KDL tree from a string containing xml /** Constructs a KDL tree from a string containing xml
* \param xml A string containting the xml description of the robot * \param xml A string containting the xml description of the robot
* \param tree The resulting KDL Tree * \param tree The resulting KDL Tree

View File

@ -138,6 +138,15 @@ bool treeFromFile(const string& file, Tree& tree)
return treeFromXml(&urdf_xml, tree); return treeFromXml(&urdf_xml, tree);
} }
bool treeFromParam(const string& param, Tree& tree)
{
urdf::Model robot_model;
if (!robot_model.initParam(param)){
ROS_ERROR("Could not generate robot model");
return false;
}
return treeFromUrdfModel(robot_model, tree);
}
bool treeFromString(const string& xml, Tree& tree) bool treeFromString(const string& xml, Tree& tree)
{ {