8 #include <unordered_set> 11 #include <rclcpp/rclcpp.hpp> 22 ParameterInterface(rclcpp::Node* node, std::vector<std::regex> paramWhitelistPatterns);
25 const std::chrono::duration<double>& timeout);
42 const std::string& nodeName,
43 const std::vector<std::string>& paramNames,
44 const std::chrono::duration<double>& timeout);
46 const std::string& nodeName,
const std::vector<rclcpp::Parameter>& params,
47 const std::chrono::duration<double>& timeout);
void setParamUpdateCallback(ParamUpdateFunc paramUpdateFunc)
void subscribeParams(const std::vector< std::string > ¶mNames)
ParameterInterface(rclcpp::Node *node, std::vector< std::regex > paramWhitelistPatterns)
ParamUpdateFunc _paramUpdateFunc
void setParams(const ParameterList ¶ms, 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 > ¶mNames)
bool isWhitelistedParam(const std::string ¶mName)
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 > ¶mNames, const std::chrono::duration< double > &timeout)
void setNodeParameters(rclcpp::AsyncParametersClient::SharedPtr paramClient, const std::string &nodeName, const std::vector< rclcpp::Parameter > ¶ms, const std::chrono::duration< double > &timeout)
ParameterList getParams(const std::vector< std::string > ¶mNames, const std::chrono::duration< double > &timeout)