From ab7c9d7b5560985a68f70e00505aea9139459397 Mon Sep 17 00:00:00 2001 From: Piyush Khandelwal Date: Mon, 30 Jan 2017 16:58:24 -0600 Subject: [PATCH 1/2] Allow supplying NodeHandle for initParam using new function. --- urdf/include/urdf/model.h | 3 +++ urdf/src/model.cpp | 8 +++++--- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/urdf/include/urdf/model.h b/urdf/include/urdf/model.h index f9e676a8..e9041d9d 100644 --- a/urdf/include/urdf/model.h +++ b/urdf/include/urdf/model.h @@ -44,6 +44,7 @@ #include #include #include +#include namespace urdf{ @@ -58,6 +59,8 @@ class Model: public ModelInterface 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); }; diff --git a/urdf/src/model.cpp b/urdf/src/model.cpp index 69f96b80..c0562f18 100644 --- a/urdf/src/model.cpp +++ b/urdf/src/model.cpp @@ -36,8 +36,6 @@ #include "urdf/model.h" -#include - /* we include the default parser for plain URDF files; other parsers are loaded via plugins (if available) */ #include @@ -88,7 +86,11 @@ bool Model::initFile(const std::string& filename) bool Model::initParam(const std::string& param) { - ros::NodeHandle nh; + 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 From a9e5fb8132ba30cd85f1adc92c63b19baae11a85 Mon Sep 17 00:00:00 2001 From: Piyush Khandelwal Date: Mon, 30 Jan 2017 17:35:09 -0600 Subject: [PATCH 2/2] fixed missing return statement in previous commit. --- urdf/src/model.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/urdf/src/model.cpp b/urdf/src/model.cpp index c0562f18..03cc774f 100644 --- a/urdf/src/model.cpp +++ b/urdf/src/model.cpp @@ -86,7 +86,7 @@ bool Model::initFile(const std::string& filename) bool Model::initParam(const std::string& param) { - initParamWithNodeHandle(param, ros::NodeHandle()); + return initParamWithNodeHandle(param, ros::NodeHandle()); } bool Model::initParamWithNodeHandle(const std::string& param, const ros::NodeHandle& nh)