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:
parent
621844364a
commit
3384a0a76f
|
@ -44,6 +44,7 @@
|
||||||
#include <tinyxml.h>
|
#include <tinyxml.h>
|
||||||
#include <boost/shared_ptr.hpp>
|
#include <boost/shared_ptr.hpp>
|
||||||
#include <boost/weak_ptr.hpp>
|
#include <boost/weak_ptr.hpp>
|
||||||
|
#include <ros/ros.h>
|
||||||
|
|
||||||
namespace urdf{
|
namespace urdf{
|
||||||
|
|
||||||
|
@ -58,6 +59,8 @@ public:
|
||||||
bool initFile(const std::string& filename);
|
bool initFile(const std::string& filename);
|
||||||
/// \brief Load Model given the name of a parameter on the parameter server
|
/// \brief Load Model given the name of a parameter on the parameter server
|
||||||
bool initParam(const std::string& param);
|
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
|
/// \brief Load Model from a XML-string
|
||||||
bool initString(const std::string& xmlstring);
|
bool initString(const std::string& xmlstring);
|
||||||
};
|
};
|
||||||
|
|
|
@ -36,8 +36,6 @@
|
||||||
|
|
||||||
#include "urdf/model.h"
|
#include "urdf/model.h"
|
||||||
|
|
||||||
#include <ros/ros.h>
|
|
||||||
|
|
||||||
/* we include the default parser for plain URDF files;
|
/* we include the default parser for plain URDF files;
|
||||||
other parsers are loaded via plugins (if available) */
|
other parsers are loaded via plugins (if available) */
|
||||||
#include <urdf_parser/urdf_parser.h>
|
#include <urdf_parser/urdf_parser.h>
|
||||||
|
@ -88,7 +86,11 @@ bool Model::initFile(const std::string& filename)
|
||||||
|
|
||||||
bool Model::initParam(const std::string& param)
|
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;
|
std::string xml_string;
|
||||||
|
|
||||||
// gets the location of the robot description on the parameter server
|
// gets the location of the robot description on the parameter server
|
||||||
|
|
Loading…
Reference in New Issue