Allow supplying NodeHandle for initParam (#168)

* Allow supplying NodeHandle for initParam using new function.

* fixed missing return statement in previous commit.
This commit is contained in:
Piyush Khandelwal 2017-02-09 18:53:46 -06:00 committed by Shane Loretz
parent 621844364a
commit 3384a0a76f
2 changed files with 8 additions and 3 deletions

View File

@ -44,6 +44,7 @@
#include <tinyxml.h>
#include <boost/shared_ptr.hpp>
#include <boost/weak_ptr.hpp>
#include <ros/ros.h>
namespace urdf{
@ -58,6 +59,8 @@ public:
bool initFile(const std::string& filename);
/// \brief Load Model given the name of a parameter on the parameter server
bool initParam(const std::string& param);
/// \brief Load Model given the name of a parameter on the parameter server using provided nodehandle
bool initParamWithNodeHandle(const std::string& param, const ros::NodeHandle& nh = ros::NodeHandle());
/// \brief Load Model from a XML-string
bool initString(const std::string& xmlstring);
};

View File

@ -36,8 +36,6 @@
#include "urdf/model.h"
#include <ros/ros.h>
/* we include the default parser for plain URDF files;
other parsers are loaded via plugins (if available) */
#include <urdf_parser/urdf_parser.h>
@ -88,7 +86,11 @@ bool Model::initFile(const std::string& filename)
bool Model::initParam(const std::string& param)
{
ros::NodeHandle nh;
return initParamWithNodeHandle(param, ros::NodeHandle());
}
bool Model::initParamWithNodeHandle(const std::string& param, const ros::NodeHandle& nh)
{
std::string xml_string;
// gets the location of the robot description on the parameter server