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 public:
22  ParameterInterface(rclcpp::Node* node, std::vector<std::regex> paramWhitelistPatterns);
23 
24  ParameterList getParams(const std::vector<std::string>& paramNames,
25  const std::chrono::duration<double>& timeout);
26  void setParams(const ParameterList& params, const std::chrono::duration<double>& timeout);
27  void subscribeParams(const std::vector<std::string>& paramNames);
28  void unsubscribeParams(const std::vector<std::string>& paramNames);
29  void setParamUpdateCallback(ParamUpdateFunc paramUpdateFunc);
30 
31 private:
32  rclcpp::Node* _node;
33  std::vector<std::regex> _paramWhitelistPatterns;
34  rclcpp::CallbackGroup::SharedPtr _callbackGroup;
35  std::mutex _mutex;
36  std::unordered_map<std::string, rclcpp::AsyncParametersClient::SharedPtr> _paramClientsByNode;
37  std::unordered_map<std::string, std::unordered_set<std::string>> _subscribedParamsByNode;
38  std::unordered_map<std::string, rclcpp::SubscriptionBase::SharedPtr> _paramSubscriptionsByNode;
40 
41  ParameterList getNodeParameters(rclcpp::AsyncParametersClient::SharedPtr paramClient,
42  const std::string& nodeName,
43  const std::vector<std::string>& paramNames,
44  const std::chrono::duration<double>& timeout);
45  void setNodeParameters(rclcpp::AsyncParametersClient::SharedPtr paramClient,
46  const std::string& nodeName, const std::vector<rclcpp::Parameter>& params,
47  const std::chrono::duration<double>& timeout);
48  bool isWhitelistedParam(const std::string& paramName);
49 };
50 
51 } // namespace foxglove_bridge
void setParamUpdateCallback(ParamUpdateFunc paramUpdateFunc)
void subscribeParams(const std::vector< std::string > &paramNames)
ParameterInterface(rclcpp::Node *node, std::vector< std::regex > paramWhitelistPatterns)
void setParams(const ParameterList &params, const std::chrono::duration< double > &timeout)
std::vector< foxglove::Parameter > ParameterList
std::function< void(const ParameterList &)> ParamUpdateFunc
rclcpp::CallbackGroup::SharedPtr _callbackGroup
std::vector< std::regex > _paramWhitelistPatterns
void unsubscribeParams(const std::vector< std::string > &paramNames)
bool isWhitelistedParam(const std::string &paramName)
std::unordered_map< std::string, rclcpp::SubscriptionBase::SharedPtr > _paramSubscriptionsByNode
std::unordered_map< std::string, rclcpp::AsyncParametersClient::SharedPtr > _paramClientsByNode
std::unordered_map< std::string, std::unordered_set< std::string > > _subscribedParamsByNode
ParameterList getNodeParameters(rclcpp::AsyncParametersClient::SharedPtr paramClient, const std::string &nodeName, const std::vector< std::string > &paramNames, const std::chrono::duration< double > &timeout)
void setNodeParameters(rclcpp::AsyncParametersClient::SharedPtr paramClient, const std::string &nodeName, const std::vector< rclcpp::Parameter > &params, const std::chrono::duration< double > &timeout)
ParameterList getParams(const std::vector< std::string > &paramNames, const std::chrono::duration< double > &timeout)


foxglove_bridge
Author(s): Foxglove
autogenerated on Mon Jul 3 2023 02:12:22