Skip to content

Commit

Permalink
Add subgroup location for private namespace params
Browse files Browse the repository at this point in the history
Rewrite comment with lookup order pattern
  • Loading branch information
henningkayser committed Dec 8, 2017
1 parent 3730d57 commit 73d4df3
Showing 1 changed file with 14 additions and 4 deletions.
Expand Up @@ -602,17 +602,27 @@ class KinematicsBase

/**
* @brief Enables kinematics plugins access to parameters that are defined
* for the 'robot_description_kinematics' namespace.
* Parameters are queried in order of the specified group hierarchy.
* That is parameters are first searched in the private namespace
* then in the subroup namespace and finally in the group namespace.
* for the private namespace and inside 'robot_description_kinematics'.
* Parameters are searched in the following locations and order
*
* ~/<group_name>/<param>
* ~/<param>
* robot_description_kinematics/<group_name>/<param>
* robot_description_kinematics/<param>
*
* This order maintains default behavior by keeping the private namespace
* as the predominant configuration but also allows groupwise specifications.
*/
template <typename T>
inline bool lookupParam(const std::string& param, T& val, const T& default_val) const
{
ros::NodeHandle pnh("~");
if (pnh.hasParam(group_name_ + "/" + param))
{
val = pnh.param(group_name_ + "/" + param, default_val);
return true;
}

if (pnh.hasParam(param))
{
val = pnh.param(param, default_val);
Expand Down

0 comments on commit 73d4df3

Please sign in to comment.