Skip to content
This repository has been archived by the owner on Aug 3, 2020. It is now read-only.

Allow supplying NodeHandle for initParam #168

Merged
merged 2 commits into from
Feb 10, 2017
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions urdf/include/urdf/model.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <tinyxml.h>
#include <boost/shared_ptr.hpp>
#include <boost/weak_ptr.hpp>
#include <ros/ros.h>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@wjwwood correct me if I'm wrong, but I think the package.xml needs <build_export_depend>roscpp</build_export_depend> because of this addition

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

build_export_depend is unsupported in package.xml format 1, which is what urdf is using. I believe the format 1 build_depend did that behavior by default.

Copy link

@mathias-luedtke mathias-luedtke Jan 31, 2017

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

AFAIK in package format 1 "exported build depends" have to be declared as run_depend.
Source: http://www.ros.org/reps/rep-0127.html#run-depend-multiple and http://www.ros.org/reps/rep-0140.html#removing-run-depend


namespace urdf{

Expand All @@ -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());
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Adding this looks good to me. It makes using the library easier.

I think the specific case of ros-controls/ros_controllers#244 could be solved by using NodeHandle::resolveName("robot_description") and passing the fully qualified name into initParam()

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@sloretz: You're right. However, after discussion, we decided to go this route.

/// \brief Load Model from a XML-string
bool initString(const std::string& xmlstring);
};
Expand Down
8 changes: 5 additions & 3 deletions urdf/src/model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down Expand Up @@ -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
Expand Down