#include <parameter_interface.hpp>
|
ParameterList | getNodeParameters (rclcpp::AsyncParametersClient::SharedPtr paramClient, const std::string &nodeName, const std::vector< std::string > ¶mNames, const std::chrono::duration< double > &timeout) |
|
bool | isWhitelistedParam (const std::string ¶mName) |
|
void | setNodeParameters (rclcpp::AsyncParametersClient::SharedPtr paramClient, const std::string &nodeName, const std::vector< rclcpp::Parameter > ¶ms, const std::chrono::duration< double > &timeout) |
|
Definition at line 20 of file parameter_interface.hpp.
◆ ParameterInterface()
foxglove_bridge::ParameterInterface::ParameterInterface |
( |
rclcpp::Node * |
node, |
|
|
std::vector< std::regex > |
paramWhitelistPatterns |
|
) |
| |
◆ getNodeParameters()
ParameterList foxglove_bridge::ParameterInterface::getNodeParameters |
( |
rclcpp::AsyncParametersClient::SharedPtr |
paramClient, |
|
|
const std::string & |
nodeName, |
|
|
const std::vector< std::string > & |
paramNames, |
|
|
const std::chrono::duration< double > & |
timeout |
|
) |
| |
|
private |
◆ getParams()
ParameterList foxglove_bridge::ParameterInterface::getParams |
( |
const std::vector< std::string > & |
paramNames, |
|
|
const std::chrono::duration< double > & |
timeout |
|
) |
| |
◆ isWhitelistedParam()
bool foxglove_bridge::ParameterInterface::isWhitelistedParam |
( |
const std::string & |
paramName | ) |
|
|
private |
◆ setNodeParameters()
void foxglove_bridge::ParameterInterface::setNodeParameters |
( |
rclcpp::AsyncParametersClient::SharedPtr |
paramClient, |
|
|
const std::string & |
nodeName, |
|
|
const std::vector< rclcpp::Parameter > & |
params, |
|
|
const std::chrono::duration< double > & |
timeout |
|
) |
| |
|
private |
◆ setParams()
void foxglove_bridge::ParameterInterface::setParams |
( |
const ParameterList & |
params, |
|
|
const std::chrono::duration< double > & |
timeout |
|
) |
| |
◆ setParamUpdateCallback()
void foxglove_bridge::ParameterInterface::setParamUpdateCallback |
( |
ParamUpdateFunc |
paramUpdateFunc | ) |
|
◆ subscribeParams()
void foxglove_bridge::ParameterInterface::subscribeParams |
( |
const std::vector< std::string > & |
paramNames | ) |
|
◆ unsubscribeParams()
void foxglove_bridge::ParameterInterface::unsubscribeParams |
( |
const std::vector< std::string > & |
paramNames | ) |
|
◆ _callbackGroup
rclcpp::CallbackGroup::SharedPtr foxglove_bridge::ParameterInterface::_callbackGroup |
|
private |
◆ _mutex
std::mutex foxglove_bridge::ParameterInterface::_mutex |
|
private |
◆ _node
rclcpp::Node* foxglove_bridge::ParameterInterface::_node |
|
private |
◆ _paramClientsByNode
std::unordered_map<std::string, rclcpp::AsyncParametersClient::SharedPtr> foxglove_bridge::ParameterInterface::_paramClientsByNode |
|
private |
◆ _paramSubscriptionsByNode
std::unordered_map<std::string, rclcpp::SubscriptionBase::SharedPtr> foxglove_bridge::ParameterInterface::_paramSubscriptionsByNode |
|
private |
◆ _paramUpdateFunc
◆ _paramWhitelistPatterns
std::vector<std::regex> foxglove_bridge::ParameterInterface::_paramWhitelistPatterns |
|
private |
◆ _subscribedParamsByNode
std::unordered_map<std::string, std::unordered_set<std::string> > foxglove_bridge::ParameterInterface::_subscribedParamsByNode |
|
private |
The documentation for this class was generated from the following files: