diff --git a/urdf/include/urdf/model.h b/urdf/include/urdf/model.h index f9e676a8..172b3529 100644 --- a/urdf/include/urdf/model.h +++ b/urdf/include/urdf/model.h @@ -44,6 +44,7 @@ #include #include #include +#include namespace urdf{ @@ -57,7 +58,7 @@ class Model: public ModelInterface /// \brief Load Model given a filename 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); + bool initParam(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 a7210564..a7534285 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 @@ -86,9 +84,8 @@ bool Model::initFile(const std::string& filename) } -bool Model::initParam(const std::string& param) +bool Model::initParam(const std::string& param, const ros::NodeHandle& nh) { - ros::NodeHandle nh; std::string xml_string; // gets the location of the robot description on the parameter server diff --git a/urdf/test/test_robot_model_parser.cpp b/urdf/test/test_robot_model_parser.cpp index f6286a53..1a146d34 100644 --- a/urdf/test/test_robot_model_parser.cpp +++ b/urdf/test/test_robot_model_parser.cpp @@ -36,7 +36,7 @@ #include #include -#include "urdf/model.h" +#include // Including ros, just to be able to call ros::init(), to remove unwanted // args from command-line.