Added basic hook for parameter changes (#244)
* Added basic hook for parameter changes * Rename hook and add docblock
This commit is contained in:
parent
8c5f6e4e06
commit
1402715d76
3 changed files with 30 additions and 4 deletions
|
@ -353,6 +353,14 @@ public:
|
|||
size_t
|
||||
count_graph_users();
|
||||
|
||||
/// Register the callback for parameter changes
|
||||
/**
|
||||
* \param[in] User defined callback function, It is expected to atomically set parameters.
|
||||
* \note Repeated invocations of this function will overwrite previous callbacks
|
||||
*/
|
||||
template<typename CallbackT>
|
||||
void register_param_change_callback(CallbackT && callback);
|
||||
|
||||
std::atomic_bool has_executor;
|
||||
|
||||
private:
|
||||
|
@ -400,6 +408,10 @@ private:
|
|||
/* graph_users_count_ is atomic so that it can be accessed without acquiring the graph_mutex_ */
|
||||
std::atomic_size_t graph_users_count_;
|
||||
|
||||
std::function<typename rcl_interfaces::msg::SetParametersResult(
|
||||
const typename std::vector<rclcpp::parameter::ParameterVariant> &
|
||||
)> parameters_callback_ = nullptr;
|
||||
|
||||
std::map<std::string, rclcpp::parameter::ParameterVariant> parameters_;
|
||||
|
||||
publisher::Publisher<rcl_interfaces::msg::ParameterEvent>::SharedPtr events_publisher_;
|
||||
|
|
|
@ -362,6 +362,12 @@ Node::create_service(
|
|||
return serv;
|
||||
}
|
||||
|
||||
template<typename CallbackT>
|
||||
void Node::register_param_change_callback(CallbackT && callback)
|
||||
{
|
||||
this->parameters_callback_ = callback;
|
||||
}
|
||||
|
||||
} // namespace node
|
||||
} // namespace rclcpp
|
||||
|
||||
|
|
|
@ -189,6 +189,18 @@ Node::set_parameters_atomically(
|
|||
std::map<std::string, rclcpp::parameter::ParameterVariant> tmp_map;
|
||||
auto parameter_event = std::make_shared<rcl_interfaces::msg::ParameterEvent>();
|
||||
|
||||
// TODO(jacquelinekay): handle parameter constraints
|
||||
rcl_interfaces::msg::SetParametersResult result;
|
||||
if (parameters_callback_) {
|
||||
result = parameters_callback_(parameters);
|
||||
} else {
|
||||
result.successful = true;
|
||||
}
|
||||
|
||||
if (!result.successful) {
|
||||
return result;
|
||||
}
|
||||
|
||||
for (auto p : parameters) {
|
||||
if (parameters_.find(p.get_name()) == parameters_.end()) {
|
||||
if (p.get_type() != rclcpp::parameter::ParameterType::PARAMETER_NOT_SET) {
|
||||
|
@ -206,10 +218,6 @@ Node::set_parameters_atomically(
|
|||
tmp_map.insert(parameters_.begin(), parameters_.end());
|
||||
std::swap(tmp_map, parameters_);
|
||||
|
||||
// TODO(jacquelinekay): handle parameter constraints
|
||||
rcl_interfaces::msg::SetParametersResult result;
|
||||
result.successful = true;
|
||||
|
||||
events_publisher_->publish(parameter_event);
|
||||
|
||||
return result;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue