parameter_interface.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <chrono>
4 #include <functional>
5 #include <mutex>
6 #include <regex>
7 #include <string>
8 #include <unordered_set>
9 #include <vector>
10 
11 #include <rclcpp/rclcpp.hpp>
12 
14 
15 namespace foxglove_bridge {
16 
17 using ParameterList = std::vector<foxglove::Parameter>;
18 using ParamUpdateFunc = std::function<void(const ParameterList&)>;
19 
21  Ignore,
22  Retry,
23 };
24 
26 public:
27  ParameterInterface(rclcpp::Node* node, std::vector<std::regex> paramWhitelistPatterns,
28  UnresponsiveNodePolicy unresponsiveNodePolicy);
29 
30  ParameterList getParams(const std::vector<std::string>& paramNames,
31  const std::chrono::duration<double>& timeout);
32  void setParams(const ParameterList& params, const std::chrono::duration<double>& timeout);
33  void subscribeParams(const std::vector<std::string>& paramNames);
34  void unsubscribeParams(const std::vector<std::string>& paramNames);
35  void setParamUpdateCallback(ParamUpdateFunc paramUpdateFunc);
36 
37 private:
38  rclcpp::Node* _node;
39  std::vector<std::regex> _paramWhitelistPatterns;
40  rclcpp::CallbackGroup::SharedPtr _callbackGroup;
41  std::mutex _mutex;
42  std::unordered_map<std::string, rclcpp::AsyncParametersClient::SharedPtr> _paramClientsByNode;
43  std::unordered_map<std::string, std::unordered_set<std::string>> _subscribedParamsByNode;
44  std::unordered_map<std::string, rclcpp::SubscriptionBase::SharedPtr> _paramSubscriptionsByNode;
45  std::unordered_set<std::string> _ignoredNodeNames;
48 
49  ParameterList getNodeParameters(rclcpp::AsyncParametersClient::SharedPtr paramClient,
50  const std::string& nodeName,
51  const std::vector<std::string>& paramNames,
52  const std::chrono::duration<double>& timeout);
53  void setNodeParameters(rclcpp::AsyncParametersClient::SharedPtr paramClient,
54  const std::string& nodeName, const std::vector<rclcpp::Parameter>& params,
55  const std::chrono::duration<double>& timeout);
56  bool isWhitelistedParam(const std::string& paramName);
57 };
58 
59 } // namespace foxglove_bridge
foxglove_bridge::ParameterInterface::_subscribedParamsByNode
std::unordered_map< std::string, std::unordered_set< std::string > > _subscribedParamsByNode
Definition: parameter_interface.hpp:43
foxglove_bridge::ParameterInterface::setParams
void setParams(const ParameterList &params, const std::chrono::duration< double > &timeout)
Definition: parameter_interface.cpp:246
foxglove_bridge::ParameterInterface::setNodeParameters
void setNodeParameters(rclcpp::AsyncParametersClient::SharedPtr paramClient, const std::string &nodeName, const std::vector< rclcpp::Parameter > &params, const std::chrono::duration< double > &timeout)
Definition: parameter_interface.cpp:395
foxglove_bridge::ParameterInterface::getNodeParameters
ParameterList getNodeParameters(rclcpp::AsyncParametersClient::SharedPtr paramClient, const std::string &nodeName, const std::vector< std::string > &paramNames, const std::chrono::duration< double > &timeout)
Definition: parameter_interface.cpp:360
foxglove_bridge::ParameterInterface::_unresponsiveNodePolicy
UnresponsiveNodePolicy _unresponsiveNodePolicy
Definition: parameter_interface.hpp:46
foxglove_bridge::ParameterInterface::getParams
ParameterList getParams(const std::vector< std::string > &paramNames, const std::chrono::duration< double > &timeout)
Definition: parameter_interface.cpp:146
foxglove_bridge::ParameterInterface::subscribeParams
void subscribeParams(const std::vector< std::string > &paramNames)
Definition: parameter_interface.cpp:285
foxglove_bridge::ParameterInterface::_paramClientsByNode
std::unordered_map< std::string, rclcpp::AsyncParametersClient::SharedPtr > _paramClientsByNode
Definition: parameter_interface.hpp:42
foxglove_bridge::ParameterInterface::isWhitelistedParam
bool isWhitelistedParam(const std::string &paramName)
foxglove_bridge::ParamUpdateFunc
std::function< void(const ParameterList &)> ParamUpdateFunc
Definition: parameter_interface.hpp:18
foxglove_bridge::ParameterInterface::setParamUpdateCallback
void setParamUpdateCallback(ParamUpdateFunc paramUpdateFunc)
Definition: parameter_interface.cpp:355
foxglove_bridge::ParameterInterface::_paramUpdateFunc
ParamUpdateFunc _paramUpdateFunc
Definition: parameter_interface.hpp:47
foxglove_bridge::ParameterInterface::unsubscribeParams
void unsubscribeParams(const std::vector< std::string > &paramNames)
Definition: parameter_interface.cpp:337
foxglove_bridge
Definition: generic_service.hpp:9
foxglove_bridge::ParameterInterface::_node
rclcpp::Node * _node
Definition: parameter_interface.hpp:38
foxglove_bridge::UnresponsiveNodePolicy
UnresponsiveNodePolicy
Definition: parameter_interface.hpp:20
foxglove_bridge::UnresponsiveNodePolicy::Retry
@ Retry
foxglove_bridge::UnresponsiveNodePolicy::Ignore
@ Ignore
foxglove_bridge::ParameterInterface::_ignoredNodeNames
std::unordered_set< std::string > _ignoredNodeNames
Definition: parameter_interface.hpp:45
foxglove_bridge::ParameterList
std::vector< foxglove::Parameter > ParameterList
Definition: parameter_interface.hpp:17
parameter.hpp
foxglove_bridge::ParameterInterface::_paramWhitelistPatterns
std::vector< std::regex > _paramWhitelistPatterns
Definition: parameter_interface.hpp:39
foxglove_bridge::ParameterInterface::_callbackGroup
rclcpp::CallbackGroup::SharedPtr _callbackGroup
Definition: parameter_interface.hpp:40
foxglove_bridge::ParameterInterface
Definition: parameter_interface.hpp:25
foxglove_bridge::ParameterInterface::_paramSubscriptionsByNode
std::unordered_map< std::string, rclcpp::SubscriptionBase::SharedPtr > _paramSubscriptionsByNode
Definition: parameter_interface.hpp:44
foxglove_bridge::ParameterInterface::_mutex
std::mutex _mutex
Definition: parameter_interface.hpp:41
foxglove_bridge::ParameterInterface::ParameterInterface
ParameterInterface(rclcpp::Node *node, std::vector< std::regex > paramWhitelistPatterns, UnresponsiveNodePolicy unresponsiveNodePolicy)
Definition: parameter_interface.cpp:137


foxglove_bridge
Author(s): Foxglove
autogenerated on Tue May 20 2025 02:34:26