ros2_foxglove_bridge/src/param_utils.cpp
Go to the documentation of this file.
1 
2 
4 #include <foxglove_bridge/param_utils.hpp>
5 
6 namespace foxglove_bridge {
7 
8 void declareParameters(rclcpp::Node* node) {
9  auto portDescription = rcl_interfaces::msg::ParameterDescriptor{};
10  portDescription.name = PARAM_PORT;
11  portDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
12  portDescription.description = "The TCP port to bind the WebSocket server to";
13  portDescription.read_only = true;
14  portDescription.additional_constraints =
15  "Must be a valid TCP port number, or 0 to use a random port";
16  portDescription.integer_range.resize(1);
17  portDescription.integer_range[0].from_value = 0;
18  portDescription.integer_range[0].to_value = 65535;
19  portDescription.integer_range[0].step = 1;
20  node->declare_parameter(PARAM_PORT, DEFAULT_PORT, portDescription);
21 
22  auto addressDescription = rcl_interfaces::msg::ParameterDescriptor{};
23  addressDescription.name = PARAM_ADDRESS;
24  addressDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING;
25  addressDescription.description = "The host address to bind the WebSocket server to";
26  addressDescription.read_only = true;
27  node->declare_parameter(PARAM_ADDRESS, DEFAULT_ADDRESS, addressDescription);
28 
29  auto sendBufferLimitDescription = rcl_interfaces::msg::ParameterDescriptor{};
30  sendBufferLimitDescription.name = PARAM_SEND_BUFFER_LIMIT;
31  sendBufferLimitDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
32  sendBufferLimitDescription.description =
33  "Connection send buffer limit in bytes. Messages will be dropped when a connection's send "
34  "buffer reaches this limit to avoid a queue of outdated messages building up.";
35  sendBufferLimitDescription.integer_range.resize(1);
36  sendBufferLimitDescription.integer_range[0].from_value = 0;
37  sendBufferLimitDescription.integer_range[0].to_value = std::numeric_limits<int64_t>::max();
38  sendBufferLimitDescription.read_only = true;
39  node->declare_parameter(PARAM_SEND_BUFFER_LIMIT, DEFAULT_SEND_BUFFER_LIMIT,
40  sendBufferLimitDescription);
41 
42  auto useTlsDescription = rcl_interfaces::msg::ParameterDescriptor{};
43  useTlsDescription.name = PARAM_USETLS;
44  useTlsDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL;
45  useTlsDescription.description = "Use Transport Layer Security for encrypted communication";
46  useTlsDescription.read_only = true;
47  node->declare_parameter(PARAM_USETLS, false, useTlsDescription);
48 
49  auto certfileDescription = rcl_interfaces::msg::ParameterDescriptor{};
50  certfileDescription.name = PARAM_CERTFILE;
51  certfileDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING;
52  certfileDescription.description = "Path to the certificate to use for TLS";
53  certfileDescription.read_only = true;
54  node->declare_parameter(PARAM_CERTFILE, "", certfileDescription);
55 
56  auto keyfileDescription = rcl_interfaces::msg::ParameterDescriptor{};
57  keyfileDescription.name = PARAM_KEYFILE;
58  keyfileDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING;
59  keyfileDescription.description = "Path to the private key to use for TLS";
60  keyfileDescription.read_only = true;
61  node->declare_parameter(PARAM_KEYFILE, "", keyfileDescription);
62 
63  auto minQosDepthDescription = rcl_interfaces::msg::ParameterDescriptor{};
64  minQosDepthDescription.name = PARAM_MIN_QOS_DEPTH;
65  minQosDepthDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
66  minQosDepthDescription.description = "Minimum depth used for the QoS profile of subscriptions.";
67  minQosDepthDescription.read_only = true;
68  minQosDepthDescription.additional_constraints = "Must be a non-negative integer";
69  minQosDepthDescription.integer_range.resize(1);
70  minQosDepthDescription.integer_range[0].from_value = 0;
71  minQosDepthDescription.integer_range[0].to_value = INT32_MAX;
72  minQosDepthDescription.integer_range[0].step = 1;
73  node->declare_parameter(PARAM_MIN_QOS_DEPTH, DEFAULT_MIN_QOS_DEPTH, minQosDepthDescription);
74 
75  auto maxQosDepthDescription = rcl_interfaces::msg::ParameterDescriptor{};
76  maxQosDepthDescription.name = PARAM_MAX_QOS_DEPTH;
77  maxQosDepthDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
78  maxQosDepthDescription.description = "Maximum depth used for the QoS profile of subscriptions.";
79  maxQosDepthDescription.read_only = true;
80  maxQosDepthDescription.additional_constraints = "Must be a non-negative integer";
81  maxQosDepthDescription.integer_range.resize(1);
82  maxQosDepthDescription.integer_range[0].from_value = 0;
83  maxQosDepthDescription.integer_range[0].to_value = INT32_MAX;
84  maxQosDepthDescription.integer_range[0].step = 1;
85  node->declare_parameter(PARAM_MAX_QOS_DEPTH, DEFAULT_MAX_QOS_DEPTH, maxQosDepthDescription);
86 
87  auto bestEffortQosTopicWhiteListDescription = rcl_interfaces::msg::ParameterDescriptor{};
88  bestEffortQosTopicWhiteListDescription.name = PARAM_BEST_EFFORT_QOS_TOPIC_WHITELIST;
89  bestEffortQosTopicWhiteListDescription.type =
90  rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
91  bestEffortQosTopicWhiteListDescription.description =
92  "List of regular expressions (ECMAScript) for topics that should be forced to use "
93  "'best_effort' QoS. Unmatched topics will use 'reliable' QoS if ALL publishers are 'reliable', "
94  "'best_effort' if any publishers are 'best_effort'.";
95  bestEffortQosTopicWhiteListDescription.read_only = true;
96  node->declare_parameter(PARAM_BEST_EFFORT_QOS_TOPIC_WHITELIST, std::vector<std::string>({"(?!)"}),
97  bestEffortQosTopicWhiteListDescription);
98 
99  auto topicWhiteListDescription = rcl_interfaces::msg::ParameterDescriptor{};
100  topicWhiteListDescription.name = PARAM_TOPIC_WHITELIST;
101  topicWhiteListDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
102  topicWhiteListDescription.description =
103  "List of regular expressions (ECMAScript) of whitelisted topic names.";
104  topicWhiteListDescription.read_only = true;
105  node->declare_parameter(PARAM_TOPIC_WHITELIST, std::vector<std::string>({".*"}),
106  topicWhiteListDescription);
107 
108  auto serviceWhiteListDescription = rcl_interfaces::msg::ParameterDescriptor{};
109  serviceWhiteListDescription.name = PARAM_SERVICE_WHITELIST;
110  serviceWhiteListDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
111  serviceWhiteListDescription.description =
112  "List of regular expressions (ECMAScript) of whitelisted service names.";
113  serviceWhiteListDescription.read_only = true;
114  node->declare_parameter(PARAM_SERVICE_WHITELIST, std::vector<std::string>({".*"}),
115  serviceWhiteListDescription);
116 
117  auto paramWhiteListDescription = rcl_interfaces::msg::ParameterDescriptor{};
118  paramWhiteListDescription.name = PARAM_PARAMETER_WHITELIST;
119  paramWhiteListDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
120  paramWhiteListDescription.description =
121  "List of regular expressions (ECMAScript) of whitelisted parameter names.";
122  paramWhiteListDescription.read_only = true;
123  node->declare_parameter(PARAM_PARAMETER_WHITELIST, std::vector<std::string>({".*"}),
124  paramWhiteListDescription);
125 
126  auto useCompressionDescription = rcl_interfaces::msg::ParameterDescriptor{};
127  useCompressionDescription.name = PARAM_USE_COMPRESSION;
128  useCompressionDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL;
129  useCompressionDescription.description =
130  "Use websocket compression (permessage-deflate). Suited for connections with smaller bandwith, "
131  "at the cost of additional CPU load.";
132  useCompressionDescription.read_only = true;
133  node->declare_parameter(PARAM_USE_COMPRESSION, false, useCompressionDescription);
134 
135  auto paramCapabilities = rcl_interfaces::msg::ParameterDescriptor{};
136  paramCapabilities.name = PARAM_CAPABILITIES;
137  paramCapabilities.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
138  paramCapabilities.description = "Server capabilities";
139  paramCapabilities.read_only = true;
140  node->declare_parameter(
142  std::vector<std::string>(std::vector<std::string>(foxglove::DEFAULT_CAPABILITIES.begin(),
144  paramCapabilities);
145 
146  auto clientTopicWhiteListDescription = rcl_interfaces::msg::ParameterDescriptor{};
147  clientTopicWhiteListDescription.name = PARAM_CLIENT_TOPIC_WHITELIST;
148  clientTopicWhiteListDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
149  clientTopicWhiteListDescription.description =
150  "List of regular expressions (ECMAScript) of whitelisted client-published topic names.";
151  clientTopicWhiteListDescription.read_only = true;
152  node->declare_parameter(PARAM_CLIENT_TOPIC_WHITELIST, std::vector<std::string>({".*"}),
153  paramWhiteListDescription);
154 
155  auto includeHiddenDescription = rcl_interfaces::msg::ParameterDescriptor{};
156  includeHiddenDescription.name = PARAM_INCLUDE_HIDDEN;
157  includeHiddenDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL;
158  includeHiddenDescription.description = "Include hidden topics and services";
159  includeHiddenDescription.read_only = true;
160  node->declare_parameter(PARAM_INCLUDE_HIDDEN, false, includeHiddenDescription);
161 
162  auto disableLoanMessageDescription = rcl_interfaces::msg::ParameterDescriptor{};
163  disableLoanMessageDescription.name = PARAM_DISABLE_LOAN_MESSAGE;
164  disableLoanMessageDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL;
165  disableLoanMessageDescription.description =
166  "Do not publish as loaned message when publishing a client message";
167  disableLoanMessageDescription.read_only = true;
168  node->declare_parameter(PARAM_DISABLE_LOAN_MESSAGE, true, disableLoanMessageDescription);
169 
170  auto assetUriAllowlistDescription = rcl_interfaces::msg::ParameterDescriptor{};
171  assetUriAllowlistDescription.name = PARAM_ASSET_URI_ALLOWLIST;
172  assetUriAllowlistDescription.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
173  assetUriAllowlistDescription.description =
174  "List of regular expressions (ECMAScript) of whitelisted asset URIs.";
175  assetUriAllowlistDescription.read_only = true;
176  node->declare_parameter(
178  std::vector<std::string>(
179  {"^package://(?:\\w+/"
180  ")*\\w+\\.(?:dae|fbx|glb|gltf|jpeg|jpg|mtl|obj|png|stl|tif|tiff|urdf|webp|xacro)$"}),
181  paramWhiteListDescription);
182 }
183 
184 std::vector<std::regex> parseRegexStrings(rclcpp::Node* node,
185  const std::vector<std::string>& strings) {
186  std::vector<std::regex> regexVector;
187  regexVector.reserve(strings.size());
188 
189  for (const auto& pattern : strings) {
190  try {
191  regexVector.push_back(
192  std::regex(pattern, std::regex_constants::ECMAScript | std::regex_constants::icase));
193  } catch (const std::exception& ex) {
194  RCLCPP_ERROR(node->get_logger(), "Ignoring invalid regular expression '%s': %s",
195  pattern.c_str(), ex.what());
196  }
197  }
198 
199  return regexVector;
200 }
201 
202 } // namespace foxglove_bridge
foxglove_bridge::PARAM_BEST_EFFORT_QOS_TOPIC_WHITELIST
constexpr char PARAM_BEST_EFFORT_QOS_TOPIC_WHITELIST[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:19
foxglove_bridge::PARAM_INCLUDE_HIDDEN
constexpr char PARAM_INCLUDE_HIDDEN[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:26
foxglove_bridge::parseRegexStrings
std::vector< std::regex > parseRegexStrings(rclcpp::Node *node, const std::vector< std::string > &strings)
Definition: ros2_foxglove_bridge/src/param_utils.cpp:184
common.hpp
foxglove_bridge::PARAM_CLIENT_TOPIC_WHITELIST
constexpr char PARAM_CLIENT_TOPIC_WHITELIST[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:25
foxglove_bridge::PARAM_PARAMETER_WHITELIST
constexpr char PARAM_PARAMETER_WHITELIST[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:22
foxglove_bridge::DEFAULT_MIN_QOS_DEPTH
constexpr int64_t DEFAULT_MIN_QOS_DEPTH
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:33
foxglove_bridge::declareParameters
void declareParameters(rclcpp::Node *node)
Definition: ros2_foxglove_bridge/src/param_utils.cpp:8
foxglove_bridge::PARAM_PORT
constexpr char PARAM_PORT[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:11
foxglove_bridge::DEFAULT_ADDRESS
constexpr char DEFAULT_ADDRESS[]
Definition: ros1_foxglove_bridge_nodelet.cpp:44
foxglove_bridge::PARAM_SEND_BUFFER_LIMIT
constexpr char PARAM_SEND_BUFFER_LIMIT[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:13
foxglove_bridge::PARAM_DISABLE_LOAN_MESSAGE
constexpr char PARAM_DISABLE_LOAN_MESSAGE[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:27
foxglove::DEFAULT_CAPABILITIES
constexpr std::array< const char *, 6 > DEFAULT_CAPABILITIES
Definition: common.hpp:21
foxglove_bridge
Definition: generic_service.hpp:9
foxglove_bridge::DEFAULT_MAX_QOS_DEPTH
constexpr int64_t DEFAULT_MAX_QOS_DEPTH
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:34
foxglove_bridge::DEFAULT_PORT
constexpr int DEFAULT_PORT
Definition: ros1_foxglove_bridge_nodelet.cpp:43
foxglove_bridge::PARAM_SERVICE_WHITELIST
constexpr char PARAM_SERVICE_WHITELIST[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:21
foxglove_bridge::PARAM_TOPIC_WHITELIST
constexpr char PARAM_TOPIC_WHITELIST[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:20
foxglove_bridge::PARAM_USE_COMPRESSION
constexpr char PARAM_USE_COMPRESSION[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:23
foxglove_bridge::PARAM_ADDRESS
constexpr char PARAM_ADDRESS[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:12
foxglove_bridge::PARAM_KEYFILE
constexpr char PARAM_KEYFILE[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:16
foxglove_bridge::PARAM_USETLS
constexpr char PARAM_USETLS[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:14
foxglove_bridge::PARAM_ASSET_URI_ALLOWLIST
constexpr char PARAM_ASSET_URI_ALLOWLIST[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:28
foxglove_bridge::PARAM_MAX_QOS_DEPTH
constexpr char PARAM_MAX_QOS_DEPTH[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:18
foxglove_bridge::DEFAULT_SEND_BUFFER_LIMIT
constexpr int64_t DEFAULT_SEND_BUFFER_LIMIT
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:32
foxglove_bridge::PARAM_CERTFILE
constexpr char PARAM_CERTFILE[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:15
foxglove_bridge::PARAM_MIN_QOS_DEPTH
constexpr char PARAM_MIN_QOS_DEPTH[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:17
foxglove_bridge::PARAM_CAPABILITIES
constexpr char PARAM_CAPABILITIES[]
Definition: ros2_foxglove_bridge/include/foxglove_bridge/param_utils.hpp:24


foxglove_bridge
Author(s): Foxglove
autogenerated on Wed Mar 5 2025 03:34:31