Skip to content

Commit

Permalink
added ros1 style get_param for non-variant types
Browse files Browse the repository at this point in the history
  • Loading branch information
Rohan Agrawal committed Jul 29, 2016
1 parent 217789a commit 4cf24e1
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 0 deletions.
3 changes: 3 additions & 0 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -262,6 +262,9 @@ class Node : public std::enable_shared_from_this<Node>
const std::string & name,
rclcpp::parameter::ParameterVariant & parameter) const;

template<typename ParameterT>
bool get_parameter(const std::string & name, ParameterT & parameter) const;

RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::ParameterDescriptor>
describe_parameters(const std::vector<std::string> & names) const;
Expand Down
13 changes: 13 additions & 0 deletions rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -368,6 +368,19 @@ void Node::register_param_change_callback(CallbackT && callback)
this->parameters_callback_ = callback;
}

template<typename ParameterT>
bool Node::get_parameter(const std::string & name, ParameterT & parameter) const
{
std::lock_guard<std::mutex> lock(mutex_);

if (parameters_.count(name)) {
parameter = parameters_.at(name).get_value<ParameterT>();
return true;
} else {
return false;
}
}

} // namespace node
} // namespace rclcpp

Expand Down

0 comments on commit 4cf24e1

Please sign in to comment.