ros1_foxglove_bridge_nodelet.cpp
Go to the documentation of this file.
1 #include <atomic>
2 #include <functional>
3 #include <memory>
4 #include <mutex>
5 #include <regex>
6 #include <shared_mutex>
7 #include <string>
8 #include <unordered_set>
9 
10 #include <nodelet/nodelet.h>
13 #include <ros/message_event.h>
14 #include <ros/ros.h>
15 #include <ros/xmlrpc_manager.h>
16 #include <ros_babel_fish/babel_fish_message.h>
17 #include <ros_babel_fish/generation/providers/integrated_description_provider.h>
18 #include <rosgraph_msgs/Clock.h>
19 #include <websocketpp/common/connection_hdl.hpp>
20 
23 #include <foxglove_bridge/param_utils.hpp>
28 
29 namespace {
30 
31 inline std::unordered_set<std::string> rpcValueToStringSet(const XmlRpc::XmlRpcValue& v) {
32  std::unordered_set<std::string> set;
33  for (int i = 0; i < v.size(); ++i) {
34  set.insert(v[i]);
35  }
36  return set;
37 }
38 
39 } // namespace
40 
41 namespace foxglove_bridge {
42 
43 constexpr int DEFAULT_PORT = 8765;
44 constexpr char DEFAULT_ADDRESS[] = "0.0.0.0";
45 constexpr int DEFAULT_MAX_UPDATE_MS = 5000;
46 constexpr char ROS1_CHANNEL_ENCODING[] = "ros1";
47 constexpr uint32_t SUBSCRIPTION_QUEUE_LENGTH = 10;
48 constexpr double MIN_UPDATE_PERIOD_MS = 100.0;
49 constexpr uint32_t PUBLICATION_QUEUE_LENGTH = 10;
51 constexpr int MAX_INVALID_PARAMS_TRACKED = 1000;
52 
53 using ConnectionHandle = websocketpp::connection_hdl;
54 using TopicAndDatatype = std::pair<std::string, std::string>;
55 using SubscriptionsByClient = std::map<ConnectionHandle, ros::Subscriber, std::owner_less<>>;
56 using ClientPublications = std::unordered_map<foxglove::ClientChannelId, ros::Publisher>;
57 using PublicationsByClient = std::map<ConnectionHandle, ClientPublications, std::owner_less<>>;
59 
61 public:
62  FoxgloveBridge() = default;
63  virtual void onInit() {
64  auto& nhp = getPrivateNodeHandle();
65  const auto address = nhp.param<std::string>("address", DEFAULT_ADDRESS);
66  const int port = nhp.param<int>("port", DEFAULT_PORT);
67  const auto send_buffer_limit = static_cast<size_t>(
68  nhp.param<int>("send_buffer_limit", foxglove::DEFAULT_SEND_BUFFER_LIMIT_BYTES));
69  const auto useTLS = nhp.param<bool>("tls", false);
70  const auto certfile = nhp.param<std::string>("certfile", "");
71  const auto keyfile = nhp.param<std::string>("keyfile", "");
72  _maxUpdateMs = static_cast<size_t>(nhp.param<int>("max_update_ms", DEFAULT_MAX_UPDATE_MS));
73  const auto useCompression = nhp.param<bool>("use_compression", false);
74  _useSimTime = nhp.param<bool>("/use_sim_time", false);
75  const auto sessionId = nhp.param<std::string>("/run_id", std::to_string(std::time(nullptr)));
76  _capabilities = nhp.param<std::vector<std::string>>(
77  "capabilities", std::vector<std::string>(foxglove::DEFAULT_CAPABILITIES.begin(),
79  _serviceRetrievalTimeoutMs = nhp.param<int>("service_type_retrieval_timeout_ms",
81 
82  const auto topicWhitelistPatterns =
83  nhp.param<std::vector<std::string>>("topic_whitelist", {".*"});
84  _topicWhitelistPatterns = parseRegexPatterns(topicWhitelistPatterns);
85  if (topicWhitelistPatterns.size() != _topicWhitelistPatterns.size()) {
86  ROS_ERROR("Failed to parse one or more topic whitelist patterns");
87  }
88  const auto paramWhitelist = nhp.param<std::vector<std::string>>("param_whitelist", {".*"});
90  if (paramWhitelist.size() != _paramWhitelistPatterns.size()) {
91  ROS_ERROR("Failed to parse one or more param whitelist patterns");
92  }
93 
94  const auto serviceWhitelist = nhp.param<std::vector<std::string>>("service_whitelist", {".*"});
96  if (serviceWhitelist.size() != _serviceWhitelistPatterns.size()) {
97  ROS_ERROR("Failed to parse one or more service whitelist patterns");
98  }
99 
100  const auto clientTopicWhitelist =
101  nhp.param<std::vector<std::string>>("client_topic_whitelist", {".*"});
102  const auto clientTopicWhitelistPatterns = parseRegexPatterns(clientTopicWhitelist);
103  if (clientTopicWhitelist.size() != clientTopicWhitelistPatterns.size()) {
104  ROS_ERROR("Failed to parse one or more service whitelist patterns");
105  }
106 
107  const auto assetUriAllowlist = nhp.param<std::vector<std::string>>(
108  "asset_uri_allowlist",
109  {"^package://(?:[-\\w%]+/"
110  ")*[-\\w%]+\\.(?:dae|fbx|glb|gltf|jpeg|jpg|mtl|obj|png|stl|tif|tiff|urdf|webp|xacro)$"});
111  _assetUriAllowlistPatterns = parseRegexPatterns(assetUriAllowlist);
112  if (assetUriAllowlist.size() != _assetUriAllowlistPatterns.size()) {
113  ROS_ERROR("Failed to parse one or more asset URI whitelist patterns");
114  }
115 
116  const char* rosDistro = std::getenv("ROS_DISTRO");
117  ROS_INFO("Starting foxglove_bridge (%s, %s@%s) with %s", rosDistro,
120 
121  try {
122  foxglove::ServerOptions serverOptions;
123  serverOptions.capabilities = _capabilities;
124  if (_useSimTime) {
125  serverOptions.capabilities.push_back(foxglove::CAPABILITY_TIME);
126  }
127  serverOptions.supportedEncodings = {ROS1_CHANNEL_ENCODING};
128  serverOptions.metadata = {{"ROS_DISTRO", rosDistro}};
129  serverOptions.sendBufferLimitBytes = send_buffer_limit;
130  serverOptions.sessionId = sessionId;
131  serverOptions.useTls = useTLS;
132  serverOptions.certfile = certfile;
133  serverOptions.keyfile = keyfile;
134  serverOptions.useCompression = useCompression;
135  serverOptions.clientTopicWhitelistPatterns = clientTopicWhitelistPatterns;
136 
137  const auto logHandler =
138  std::bind(&FoxgloveBridge::logHandler, this, std::placeholders::_1, std::placeholders::_2);
139 
140  // Fetching of assets may be blocking, hence we fetch them in a separate thread.
141  _fetchAssetQueue = std::make_unique<foxglove::CallbackQueue>(logHandler, 1 /* num_threads */);
142 
143  _server = foxglove::ServerFactory::createServer<ConnectionHandle>("foxglove_bridge",
144  logHandler, serverOptions);
146  hdlrs.subscribeHandler =
147  std::bind(&FoxgloveBridge::subscribe, this, std::placeholders::_1, std::placeholders::_2);
148  hdlrs.unsubscribeHandler =
149  std::bind(&FoxgloveBridge::unsubscribe, this, std::placeholders::_1, std::placeholders::_2);
151  std::placeholders::_1, std::placeholders::_2);
153  std::placeholders::_1, std::placeholders::_2);
154  hdlrs.clientMessageHandler = std::bind(&FoxgloveBridge::clientMessage, this,
155  std::placeholders::_1, std::placeholders::_2);
157  std::bind(&FoxgloveBridge::getParameters, this, std::placeholders::_1,
158  std::placeholders::_2, std::placeholders::_3);
159  hdlrs.parameterChangeHandler =
160  std::bind(&FoxgloveBridge::setParameters, this, std::placeholders::_1,
161  std::placeholders::_2, std::placeholders::_3);
163  std::bind(&FoxgloveBridge::subscribeParameters, this, std::placeholders::_1,
164  std::placeholders::_2, std::placeholders::_3);
165  hdlrs.serviceRequestHandler = std::bind(&FoxgloveBridge::serviceRequest, this,
166  std::placeholders::_1, std::placeholders::_2);
167  hdlrs.subscribeConnectionGraphHandler = [this](bool subscribe) {
169  };
170 
172  hdlrs.fetchAssetHandler = [this](const std::string& uri, uint32_t requestId,
173  foxglove::ConnHandle hdl) {
174  _fetchAssetQueue->addCallback(
175  std::bind(&FoxgloveBridge::fetchAsset, this, uri, requestId, hdl));
176  };
177  }
178 
179  _server->setHandlers(std::move(hdlrs));
180 
181  _server->start(address, static_cast<uint16_t>(port));
182 
183  xmlrpcServer.bind("paramUpdate", std::bind(&FoxgloveBridge::parameterUpdates, this,
184  std::placeholders::_1, std::placeholders::_2));
186 
188 
189  if (_useSimTime) {
190  _clockSubscription = getMTNodeHandle().subscribe<rosgraph_msgs::Clock>(
191  "/clock", 10, [&](const rosgraph_msgs::Clock::ConstPtr msg) {
192  _server->broadcastTime(msg->clock.toNSec());
193  });
194  }
195  } catch (const std::exception& err) {
196  ROS_ERROR("Failed to start websocket server: %s", err.what());
197  // Rethrow exception such that the nodelet is unloaded.
198  throw err;
199  }
200  };
201  virtual ~FoxgloveBridge() {
203  if (_server) {
204  _server->stop();
205  }
206  }
207 
208 private:
209  struct PairHash {
210  template <class T1, class T2>
211  std::size_t operator()(const std::pair<T1, T2>& pair) const {
212  return std::hash<T1>()(pair.first) ^ std::hash<T2>()(pair.second);
213  }
214  };
215 
216  void subscribe(foxglove::ChannelId channelId, ConnectionHandle clientHandle) {
217  std::lock_guard<std::mutex> lock(_subscriptionsMutex);
218 
219  auto it = _advertisedTopics.find(channelId);
220  if (it == _advertisedTopics.end()) {
221  const std::string errMsg =
222  "Received subscribe request for unknown channel " + std::to_string(channelId);
223  ROS_WARN_STREAM(errMsg);
224  throw foxglove::ChannelError(channelId, errMsg);
225  }
226 
227  const auto& channel = it->second;
228  const auto& topic = channel.topic;
229  const auto& datatype = channel.schemaName;
230 
231  // Get client subscriptions for this channel or insert an empty map.
232  auto [subscriptionsIt, firstSubscription] =
233  _subscriptions.emplace(channelId, SubscriptionsByClient());
234  auto& subscriptionsByClient = subscriptionsIt->second;
235 
236  if (!firstSubscription &&
237  subscriptionsByClient.find(clientHandle) != subscriptionsByClient.end()) {
238  const std::string errMsg =
239  "Client is already subscribed to channel " + std::to_string(channelId);
240  ROS_WARN_STREAM(errMsg);
241  throw foxglove::ChannelError(channelId, errMsg);
242  }
243 
244  try {
245  subscriptionsByClient.emplace(
246  clientHandle, getMTNodeHandle().subscribe<ros_babel_fish::BabelFishMessage>(
248  std::bind(&FoxgloveBridge::rosMessageHandler, this, channelId, clientHandle,
249  std::placeholders::_1)));
250  if (firstSubscription) {
251  ROS_INFO("Subscribed to topic \"%s\" (%s) on channel %d", topic.c_str(), datatype.c_str(),
252  channelId);
253 
254  } else {
255  ROS_INFO("Added subscriber #%zu to topic \"%s\" (%s) on channel %d",
256  subscriptionsByClient.size(), topic.c_str(), datatype.c_str(), channelId);
257  }
258  } catch (const std::exception& ex) {
259  const std::string errMsg =
260  "Failed to subscribe to topic '" + topic + "' (" + datatype + "): " + ex.what();
261  ROS_ERROR_STREAM(errMsg);
262  throw foxglove::ChannelError(channelId, errMsg);
263  }
264  }
265 
266  void unsubscribe(foxglove::ChannelId channelId, ConnectionHandle clientHandle) {
267  std::lock_guard<std::mutex> lock(_subscriptionsMutex);
268 
269  const auto channelIt = _advertisedTopics.find(channelId);
270  if (channelIt == _advertisedTopics.end()) {
271  const std::string errMsg =
272  "Received unsubscribe request for unknown channel " + std::to_string(channelId);
273  ROS_WARN_STREAM(errMsg);
274  throw foxglove::ChannelError(channelId, errMsg);
275  }
276  const auto& channel = channelIt->second;
277 
278  auto subscriptionsIt = _subscriptions.find(channelId);
279  if (subscriptionsIt == _subscriptions.end()) {
280  throw foxglove::ChannelError(channelId, "Received unsubscribe request for channel " +
281  std::to_string(channelId) +
282  " that was not subscribed to ");
283  }
284 
285  auto& subscriptionsByClient = subscriptionsIt->second;
286  const auto clientSubscription = subscriptionsByClient.find(clientHandle);
287  if (clientSubscription == subscriptionsByClient.end()) {
289  channelId, "Received unsubscribe request for channel " + std::to_string(channelId) +
290  "from a client that was not subscribed to this channel");
291  }
292 
293  subscriptionsByClient.erase(clientSubscription);
294  if (subscriptionsByClient.empty()) {
295  ROS_INFO("Unsubscribing from topic \"%s\" (%s) on channel %d", channel.topic.c_str(),
296  channel.schemaName.c_str(), channelId);
297  _subscriptions.erase(subscriptionsIt);
298  } else {
299  ROS_INFO("Removed one subscription from channel %d (%zu subscription(s) left)", channelId,
300  subscriptionsByClient.size());
301  }
302  }
303 
305  ConnectionHandle clientHandle) {
306  if (channel.encoding != ROS1_CHANNEL_ENCODING) {
308  channel.channelId, "Unsupported encoding. Only '" + std::string(ROS1_CHANNEL_ENCODING) +
309  "' encoding is supported at the moment.");
310  }
311 
312  std::unique_lock<std::shared_mutex> lock(_publicationsMutex);
313 
314  // Get client publications or insert an empty map.
315  auto [clientPublicationsIt, isFirstPublication] =
316  _clientAdvertisedTopics.emplace(clientHandle, ClientPublications());
317 
318  auto& clientPublications = clientPublicationsIt->second;
319  if (!isFirstPublication &&
320  clientPublications.find(channel.channelId) != clientPublications.end()) {
322  channel.channelId, "Received client advertisement from " +
323  _server->remoteEndpointString(clientHandle) + " for channel " +
324  std::to_string(channel.channelId) + " it had already advertised");
325  }
326 
327  const auto msgDescription = _rosTypeInfoProvider.getMessageDescription(channel.schemaName);
328  if (!msgDescription) {
330  channel.channelId, "Failed to retrieve type information of data type '" +
331  channel.schemaName + "'. Unable to advertise topic " + channel.topic);
332  }
333 
334  ros::AdvertiseOptions advertiseOptions;
335  advertiseOptions.datatype = channel.schemaName;
336  advertiseOptions.has_header = false; // TODO
337  advertiseOptions.latch = false;
338  advertiseOptions.md5sum = msgDescription->md5;
339  advertiseOptions.message_definition = msgDescription->message_definition;
340  advertiseOptions.queue_size = PUBLICATION_QUEUE_LENGTH;
341  advertiseOptions.topic = channel.topic;
342  auto publisher = getMTNodeHandle().advertise(advertiseOptions);
343 
344  if (publisher) {
345  clientPublications.insert({channel.channelId, std::move(publisher)});
346  ROS_INFO("Client %s is advertising \"%s\" (%s) on channel %d",
347  _server->remoteEndpointString(clientHandle).c_str(), channel.topic.c_str(),
348  channel.schemaName.c_str(), channel.channelId);
349  // Trigger topic discovery so other clients are immediately informed about this new topic.
351  } else {
352  const auto errMsg =
353  "Failed to create publisher for topic " + channel.topic + "(" + channel.schemaName + ")";
354  ROS_ERROR_STREAM(errMsg);
355  throw foxglove::ClientChannelError(channel.channelId, errMsg);
356  }
357  }
358 
360  std::unique_lock<std::shared_mutex> lock(_publicationsMutex);
361 
362  auto clientPublicationsIt = _clientAdvertisedTopics.find(clientHandle);
363  if (clientPublicationsIt == _clientAdvertisedTopics.end()) {
365  channelId, "Ignoring client unadvertisement from " +
366  _server->remoteEndpointString(clientHandle) + " for unknown channel " +
367  std::to_string(channelId) + ", client has no advertised topics");
368  }
369 
370  auto& clientPublications = clientPublicationsIt->second;
371 
372  auto channelPublicationIt = clientPublications.find(channelId);
373  if (channelPublicationIt == clientPublications.end()) {
375  channelId, "Ignoring client unadvertisement from " +
376  _server->remoteEndpointString(clientHandle) + " for unknown channel " +
377  std::to_string(channelId) + ", client has " +
378  std::to_string(clientPublications.size()) + " advertised topic(s)");
379  }
380 
381  const auto& publisher = channelPublicationIt->second;
382  ROS_INFO("Client %s is no longer advertising %s (%d subscribers) on channel %d",
383  _server->remoteEndpointString(clientHandle).c_str(), publisher.getTopic().c_str(),
384  publisher.getNumSubscribers(), channelId);
385  clientPublications.erase(channelPublicationIt);
386 
387  if (clientPublications.empty()) {
388  _clientAdvertisedTopics.erase(clientPublicationsIt);
389  }
390  }
391 
392  void clientMessage(const foxglove::ClientMessage& clientMsg, ConnectionHandle clientHandle) {
393  ros_babel_fish::BabelFishMessage::Ptr msg(new ros_babel_fish::BabelFishMessage);
394  msg->read(clientMsg);
395 
396  const auto channelId = clientMsg.advertisement.channelId;
397  std::shared_lock<std::shared_mutex> lock(_publicationsMutex);
398 
399  auto clientPublicationsIt = _clientAdvertisedTopics.find(clientHandle);
400  if (clientPublicationsIt == _clientAdvertisedTopics.end()) {
402  channelId, "Dropping client message from " + _server->remoteEndpointString(clientHandle) +
403  " for unknown channel " + std::to_string(channelId) +
404  ", client has no advertised topics");
405  }
406 
407  auto& clientPublications = clientPublicationsIt->second;
408 
409  auto channelPublicationIt = clientPublications.find(clientMsg.advertisement.channelId);
410  if (channelPublicationIt == clientPublications.end()) {
412  channelId, "Dropping client message from " + _server->remoteEndpointString(clientHandle) +
413  " for unknown channel " + std::to_string(channelId) + ", client has " +
414  std::to_string(clientPublications.size()) + " advertised topic(s)");
415  }
416 
417  try {
418  channelPublicationIt->second.publish(msg);
419  } catch (const std::exception& ex) {
420  throw foxglove::ClientChannelError(channelId, "Failed to publish message on topic '" +
421  channelPublicationIt->second.getTopic() +
422  "': " + ex.what());
423  }
424  }
425 
427  _updateTimer.stop();
428  if (!ros::ok()) {
429  return;
430  }
431 
432  const bool servicesEnabled = hasCapability(foxglove::CAPABILITY_SERVICES);
433  const bool querySystemState = servicesEnabled || _subscribeGraphUpdates;
434 
435  std::vector<std::string> serviceNames;
436  foxglove::MapOfSets publishers, subscribers, services;
437 
438  // Retrieve system state from ROS master.
439  if (querySystemState) {
440  XmlRpc::XmlRpcValue params, result, payload;
441  params[0] = this->getName();
442  if (ros::master::execute("getSystemState", params, result, payload, false) &&
443  static_cast<int>(result[0]) == 1) {
444  const auto& systemState = result[2];
445  const auto& publishersXmlRpc = systemState[0];
446  const auto& subscribersXmlRpc = systemState[1];
447  const auto& servicesXmlRpc = systemState[2];
448 
449  for (int i = 0; i < servicesXmlRpc.size(); ++i) {
450  const std::string& name = servicesXmlRpc[i][0];
452  serviceNames.push_back(name);
453  services.emplace(name, rpcValueToStringSet(servicesXmlRpc[i][1]));
454  }
455  }
456  for (int i = 0; i < publishersXmlRpc.size(); ++i) {
457  const std::string& name = publishersXmlRpc[i][0];
459  publishers.emplace(name, rpcValueToStringSet(publishersXmlRpc[i][1]));
460  }
461  }
462  for (int i = 0; i < subscribersXmlRpc.size(); ++i) {
463  const std::string& name = subscribersXmlRpc[i][0];
465  subscribers.emplace(name, rpcValueToStringSet(subscribersXmlRpc[i][1]));
466  }
467  }
468  } else {
469  ROS_WARN("Failed to call getSystemState: %s", result.toXml().c_str());
470  }
471  }
472 
474  if (servicesEnabled) {
475  updateAdvertisedServices(serviceNames);
476  }
478  _server->updateConnectionGraph(publishers, subscribers, services);
479  }
480 
481  // Schedule the next update using truncated exponential backoff, between `MIN_UPDATE_PERIOD_MS`
482  // and `_maxUpdateMs`
483  _updateCount++;
484  const auto nextUpdateMs = std::max(
485  MIN_UPDATE_PERIOD_MS, static_cast<double>(std::min(size_t(1) << _updateCount, _maxUpdateMs)));
488  }
489 
491  // Get the current list of visible topics and datatypes from the ROS graph
492  // For this, we call the ros master's `getTopicTypes` method (See
493  // https://wiki.ros.org/ROS/Master_API) which also includes topics without publisher(s) and only
494  // subscriber(s).
495  XmlRpc::XmlRpcValue request, response, topicNamesAndTypes;
496  request[0] = ros::this_node::getName();
497 
498  if (!ros::master::execute("getTopicTypes", request, response, topicNamesAndTypes, false)) {
499  ROS_WARN("Failed to retrieve topics from ROS master.");
500  return;
501  }
502 
503  std::unordered_set<TopicAndDatatype, PairHash> latestTopics;
504  latestTopics.reserve(topicNamesAndTypes.size());
505  for (int i = 0; i < topicNamesAndTypes.size(); ++i) {
506  const std::string topicName = topicNamesAndTypes[i][0];
507  const std::string datatype = topicNamesAndTypes[i][1];
508 
509  // Ignore the topic if it is not on the topic whitelist
510  if (isWhitelisted(topicName, _topicWhitelistPatterns)) {
511  latestTopics.emplace(topicName, datatype);
512  }
513  }
514 
515  if (const auto numIgnoredTopics = topicNamesAndTypes.size() - latestTopics.size()) {
516  ROS_DEBUG(
517  "%zu topics have been ignored as they do not match any pattern on the topic whitelist",
518  numIgnoredTopics);
519  }
520 
521  std::lock_guard<std::mutex> lock(_subscriptionsMutex);
522 
523  // Remove channels for which the topic does not exist anymore
524  std::vector<foxglove::ChannelId> channelIdsToRemove;
525  for (auto channelIt = _advertisedTopics.begin(); channelIt != _advertisedTopics.end();) {
526  const TopicAndDatatype topicAndDatatype = {channelIt->second.topic,
527  channelIt->second.schemaName};
528  if (latestTopics.find(topicAndDatatype) == latestTopics.end()) {
529  const auto channelId = channelIt->first;
530  channelIdsToRemove.push_back(channelId);
531  _subscriptions.erase(channelId);
532  ROS_DEBUG("Removed channel %d for topic \"%s\" (%s)", channelId,
533  topicAndDatatype.first.c_str(), topicAndDatatype.second.c_str());
534  channelIt = _advertisedTopics.erase(channelIt);
535  } else {
536  channelIt++;
537  }
538  }
539  _server->removeChannels(channelIdsToRemove);
540 
541  // Add new channels for new topics
542  std::vector<foxglove::ChannelWithoutId> channelsToAdd;
543  for (const auto& topicAndDatatype : latestTopics) {
544  if (std::find_if(_advertisedTopics.begin(), _advertisedTopics.end(),
545  [topicAndDatatype](const auto& channelIdAndChannel) {
546  const auto& channel = channelIdAndChannel.second;
547  return channel.topic == topicAndDatatype.first &&
548  channel.schemaName == topicAndDatatype.second;
549  }) != _advertisedTopics.end()) {
550  continue; // Topic already advertised
551  }
552 
553  foxglove::ChannelWithoutId newChannel{};
554  newChannel.topic = topicAndDatatype.first;
555  newChannel.schemaName = topicAndDatatype.second;
556  newChannel.encoding = ROS1_CHANNEL_ENCODING;
557 
558  try {
559  const auto msgDescription =
560  _rosTypeInfoProvider.getMessageDescription(topicAndDatatype.second);
561  if (msgDescription) {
562  newChannel.schema = msgDescription->message_definition;
563  } else {
564  ROS_WARN("Could not find definition for type %s", topicAndDatatype.second.c_str());
565 
566  // We still advertise the channel, but with an emtpy schema
567  newChannel.schema = "";
568  }
569  } catch (const std::exception& err) {
570  ROS_WARN("Failed to add channel for topic \"%s\" (%s): %s", topicAndDatatype.first.c_str(),
571  topicAndDatatype.second.c_str(), err.what());
572  continue;
573  }
574 
575  channelsToAdd.push_back(newChannel);
576  }
577 
578  const auto channelIds = _server->addChannels(channelsToAdd);
579  for (size_t i = 0; i < channelsToAdd.size(); ++i) {
580  const auto channelId = channelIds[i];
581  const auto& channel = channelsToAdd[i];
582  _advertisedTopics.emplace(channelId, channel);
583  ROS_DEBUG("Advertising channel %d for topic \"%s\" (%s)", channelId, channel.topic.c_str(),
584  channel.schemaName.c_str());
585  }
586  }
587 
588  void updateAdvertisedServices(const std::vector<std::string>& serviceNames) {
589  std::unique_lock<std::shared_mutex> lock(_servicesMutex);
590 
591  // Remove advertisements for services that have been removed
592  std::vector<foxglove::ServiceId> servicesToRemove;
593  for (const auto& service : _advertisedServices) {
594  const auto it =
595  std::find_if(serviceNames.begin(), serviceNames.end(), [service](const auto& serviceName) {
596  return serviceName == service.second.name;
597  });
598  if (it == serviceNames.end()) {
599  servicesToRemove.push_back(service.first);
600  }
601  }
602  for (auto serviceId : servicesToRemove) {
603  _advertisedServices.erase(serviceId);
604  }
605  _server->removeServices(servicesToRemove);
606 
607  // Advertise new services
608  std::vector<foxglove::ServiceWithoutId> newServices;
609  for (const auto& serviceName : serviceNames) {
610  if (std::find_if(_advertisedServices.begin(), _advertisedServices.end(),
611  [&serviceName](const auto& idWithService) {
612  return idWithService.second.name == serviceName;
613  }) != _advertisedServices.end()) {
614  continue; // Already advertised
615  }
616 
617  try {
618  const auto serviceType =
619  retrieveServiceType(serviceName, std::chrono::milliseconds(_serviceRetrievalTimeoutMs));
620  const auto srvDescription = _rosTypeInfoProvider.getServiceDescription(serviceType);
621 
623  service.name = serviceName;
624  service.type = serviceType;
625 
626  if (srvDescription) {
627  service.requestSchema = srvDescription->request->message_definition;
628  service.responseSchema = srvDescription->response->message_definition;
629  } else {
630  ROS_ERROR("Failed to retrieve type information for service '%s' of type '%s'",
631  serviceName.c_str(), serviceType.c_str());
632 
633  // We still advertise the channel, but with empty schema.
634  service.requestSchema = "";
635  service.responseSchema = "";
636  }
637  newServices.push_back(service);
638  } catch (const std::exception& e) {
639  ROS_ERROR("Failed to retrieve service type or service description of service %s: %s",
640  serviceName.c_str(), e.what());
641  continue;
642  }
643  }
644 
645  const auto serviceIds = _server->addServices(newServices);
646  for (size_t i = 0; i < serviceIds.size(); ++i) {
647  _advertisedServices.emplace(serviceIds[i], newServices[i]);
648  }
649  }
650 
651  void getParameters(const std::vector<std::string>& parameters,
652  const std::optional<std::string>& requestId, ConnectionHandle hdl) {
653  const bool allParametersRequested = parameters.empty();
654  std::vector<std::string> parameterNames = parameters;
655  if (allParametersRequested) {
656  if (!getMTNodeHandle().getParamNames(parameterNames)) {
657  const auto errMsg = "Failed to retrieve parameter names";
658  ROS_ERROR_STREAM(errMsg);
659  throw std::runtime_error(errMsg);
660  }
661  }
662 
663  bool success = true;
664  std::vector<foxglove::Parameter> params;
665  std::vector<std::string> invalidParams;
666  for (const auto& paramName : parameterNames) {
667  if (!isWhitelisted(paramName, _paramWhitelistPatterns)) {
668  if (allParametersRequested) {
669  continue;
670  } else {
671  ROS_ERROR("Parameter '%s' is not on the allowlist", paramName.c_str());
672  success = false;
673  }
674  }
675  if (_invalidParams.find(paramName) != _invalidParams.end()) {
676  continue;
677  }
678 
679  try {
680  XmlRpc::XmlRpcValue value;
681  getMTNodeHandle().getParam(paramName, value);
682  params.push_back(fromRosParam(paramName, value));
683  } catch (const std::exception& ex) {
684  ROS_ERROR("Invalid parameter '%s': %s", paramName.c_str(), ex.what());
685  invalidParams.push_back(paramName);
686  success = false;
687  } catch (const XmlRpc::XmlRpcException& ex) {
688  ROS_ERROR("Invalid parameter '%s': %s", paramName.c_str(), ex.getMessage().c_str());
689  invalidParams.push_back(paramName);
690  success = false;
691  } catch (...) {
692  ROS_ERROR("Invalid parameter '%s'", paramName.c_str());
693  invalidParams.push_back(paramName);
694  success = false;
695  }
696  }
697 
698  _server->publishParameterValues(hdl, params, requestId);
699 
700  if (!success) {
701  for (std::string& param : invalidParams) {
703  _invalidParams.insert(param);
704  }
705  }
706 
707  if (!invalidParams.empty()) {
708  std::string errorMsg = "Failed to retrieve the following parameters: ";
709  for (size_t i = 0; i < invalidParams.size(); i++) {
710  errorMsg += invalidParams[i];
711  if (i < invalidParams.size() - 1) {
712  errorMsg += ", ";
713  }
714  }
715  throw std::runtime_error(errorMsg);
716  } else {
717  throw std::runtime_error("Failed to retrieve one or multiple parameters");
718  }
719  }
720  }
721 
722  void setParameters(const std::vector<foxglove::Parameter>& parameters,
723  const std::optional<std::string>& requestId, ConnectionHandle hdl) {
725  auto nh = this->getMTNodeHandle();
726 
727  bool success = true;
728  for (const auto& param : parameters) {
729  const auto paramName = param.getName();
730  if (!isWhitelisted(paramName, _paramWhitelistPatterns)) {
731  ROS_ERROR("Parameter '%s' is not on the allowlist", paramName.c_str());
732  success = false;
733  continue;
734  }
735 
736  try {
737  const auto paramType = param.getType();
738  const auto paramValue = param.getValue();
739  if (paramType == ParameterType::PARAMETER_NOT_SET) {
740  nh.deleteParam(paramName);
741  } else {
742  nh.setParam(paramName, toRosParam(paramValue));
743  }
744  } catch (const std::exception& ex) {
745  ROS_ERROR("Failed to set parameter '%s': %s", paramName.c_str(), ex.what());
746  success = false;
747  } catch (const XmlRpc::XmlRpcException& ex) {
748  ROS_ERROR("Failed to set parameter '%s': %s", paramName.c_str(), ex.getMessage().c_str());
749  success = false;
750  } catch (...) {
751  ROS_ERROR("Failed to set parameter '%s'", paramName.c_str());
752  success = false;
753  }
754  }
755 
756  // If a request Id was given, send potentially updated parameters back to client
757  if (requestId) {
758  std::vector<std::string> parameterNames(parameters.size());
759  for (size_t i = 0; i < parameters.size(); ++i) {
760  parameterNames[i] = parameters[i].getName();
761  }
762  getParameters(parameterNames, requestId, hdl);
763  }
764 
765  if (!success) {
766  throw std::runtime_error("Failed to set one or multiple parameters");
767  }
768  }
769 
770  void subscribeParameters(const std::vector<std::string>& parameters,
772  const auto opVerb =
773  (op == foxglove::ParameterSubscriptionOperation::SUBSCRIBE) ? "subscribe" : "unsubscribe";
774  bool success = true;
775  for (const auto& paramName : parameters) {
776  if (!isWhitelisted(paramName, _paramWhitelistPatterns)) {
777  ROS_ERROR("Parameter '%s' is not allowlist", paramName.c_str());
778  continue;
779  }
780 
781  XmlRpc::XmlRpcValue params, result, payload;
782  params[0] = getName() + "2";
783  params[1] = xmlrpcServer.getServerURI();
784  params[2] = ros::names::resolve(paramName);
785 
786  const std::string opName = std::string(opVerb) + "Param";
787  if (ros::master::execute(opName, params, result, payload, false)) {
788  ROS_DEBUG("%s '%s'", opName.c_str(), paramName.c_str());
789  } else {
790  ROS_WARN("Failed to %s '%s': %s", opVerb, paramName.c_str(), result.toXml().c_str());
791  success = false;
792  }
793  }
794 
795  if (!success) {
796  throw std::runtime_error("Failed to " + std::string(opVerb) + " one or multiple parameters.");
797  }
798  }
799 
801  result[0] = 1;
802  result[1] = std::string("");
803  result[2] = 0;
804 
805  if (params.size() != 3) {
806  ROS_ERROR("Parameter update called with invalid parameter size: %d", params.size());
807  return;
808  }
809 
810  try {
811  const std::string paramName = ros::names::clean(params[1]);
812  const XmlRpc::XmlRpcValue paramValue = params[2];
813  const auto param = fromRosParam(paramName, paramValue);
814  _server->updateParameterValues({param});
815  } catch (const std::exception& ex) {
816  ROS_ERROR("Failed to update parameter: %s", ex.what());
817  } catch (const XmlRpc::XmlRpcException& ex) {
818  ROS_ERROR("Failed to update parameter: %s", ex.getMessage().c_str());
819  } catch (...) {
820  ROS_ERROR("Failed to update parameter");
821  }
822  }
823 
824  void logHandler(foxglove::WebSocketLogLevel level, char const* msg) {
825  switch (level) {
827  ROS_DEBUG("[WS] %s", msg);
828  break;
830  ROS_INFO("[WS] %s", msg);
831  break;
833  ROS_WARN("[WS] %s", msg);
834  break;
836  ROS_ERROR("[WS] %s", msg);
837  break;
839  ROS_FATAL("[WS] %s", msg);
840  break;
841  }
842  }
843 
845  const foxglove::ChannelId channelId, ConnectionHandle clientHandle,
847  const auto& msg = msgEvent.getConstMessage();
848  const auto receiptTimeNs = msgEvent.getReceiptTime().toNSec();
849  _server->sendMessage(clientHandle, channelId, receiptTimeNs, msg->buffer(), msg->size());
850  }
851 
852  void serviceRequest(const foxglove::ServiceRequest& request, ConnectionHandle clientHandle) {
853  std::shared_lock<std::shared_mutex> lock(_servicesMutex);
854  const auto serviceIt = _advertisedServices.find(request.serviceId);
855  if (serviceIt == _advertisedServices.end()) {
856  const auto errMsg =
857  "Service with id " + std::to_string(request.serviceId) + " does not exist";
858  ROS_ERROR_STREAM(errMsg);
859  throw foxglove::ServiceError(request.serviceId, errMsg);
860  }
861  const auto& serviceName = serviceIt->second.name;
862  const auto& serviceType = serviceIt->second.type;
863  ROS_DEBUG("Received a service request for service %s (%s)", serviceName.c_str(),
864  serviceType.c_str());
865 
866  if (!ros::service::exists(serviceName, false)) {
867  throw foxglove::ServiceError(request.serviceId,
868  "Service '" + serviceName + "' does not exist");
869  }
870 
871  const auto srvDescription = _rosTypeInfoProvider.getServiceDescription(serviceType);
872  if (!srvDescription) {
873  const auto errMsg =
874  "Failed to retrieve type information for service " + serviceName + "(" + serviceType + ")";
875  ROS_ERROR_STREAM(errMsg);
876  throw foxglove::ServiceError(request.serviceId, errMsg);
877  }
878 
879  GenericService genReq, genRes;
880  genReq.type = genRes.type = serviceType;
881  genReq.md5sum = genRes.md5sum = srvDescription->md5;
882  genReq.data = request.data;
883 
884  if (ros::service::call(serviceName, genReq, genRes)) {
886  res.serviceId = request.serviceId;
887  res.callId = request.callId;
888  res.encoding = request.encoding;
889  res.data = genRes.data;
890  _server->sendServiceResponse(clientHandle, res);
891  } else {
893  request.serviceId, "Failed to call service " + serviceName + "(" + serviceType + ")");
894  }
895  }
896 
897  void fetchAsset(const std::string& uri, uint32_t requestId, ConnectionHandle clientHandle) {
899  response.requestId = requestId;
900 
901  try {
902  // We reject URIs that are not on the allowlist or that contain two consecutive dots. The
903  // latter can be utilized to construct URIs for retrieving confidential files that should not
904  // be accessible over the WebSocket connection. Example:
905  // `package://<pkg_name>/../../../secret.txt`. This is an extra security measure and should
906  // not be necessary if the allowlist is strict enough.
907  if (uri.find("..") != std::string::npos || !isWhitelisted(uri, _assetUriAllowlistPatterns)) {
908  throw std::runtime_error("Asset URI not allowed: " + uri);
909  }
910 
912  const resource_retriever::MemoryResource memoryResource = resource_retriever.get(uri);
914  response.errorMessage = "";
915  response.data.resize(memoryResource.size);
916  std::memcpy(response.data.data(), memoryResource.data.get(), memoryResource.size);
917  } catch (const std::exception& ex) {
918  ROS_WARN("Failed to retrieve asset '%s': %s", uri.c_str(), ex.what());
920  response.errorMessage = "Failed to retrieve asset " + uri;
921  }
922 
923  if (_server) {
924  _server->sendFetchAssetResponse(clientHandle, response);
925  }
926  }
927 
928  bool hasCapability(const std::string& capability) {
929  return std::find(_capabilities.begin(), _capabilities.end(), capability) != _capabilities.end();
930  }
931 
932  std::unique_ptr<foxglove::ServerInterface<ConnectionHandle>> _server;
933  ros_babel_fish::IntegratedDescriptionProvider _rosTypeInfoProvider;
934  std::vector<std::regex> _topicWhitelistPatterns;
935  std::vector<std::regex> _paramWhitelistPatterns;
936  std::vector<std::regex> _serviceWhitelistPatterns;
937  std::vector<std::regex> _assetUriAllowlistPatterns;
939  std::unordered_map<foxglove::ChannelId, foxglove::ChannelWithoutId> _advertisedTopics;
940  std::unordered_map<foxglove::ChannelId, SubscriptionsByClient> _subscriptions;
941  std::unordered_map<foxglove::ServiceId, foxglove::ServiceWithoutId> _advertisedServices;
944  std::shared_mutex _publicationsMutex;
945  std::shared_mutex _servicesMutex;
948  size_t _updateCount = 0;
950  bool _useSimTime = false;
951  std::vector<std::string> _capabilities;
953  std::atomic<bool> _subscribeGraphUpdates = false;
954  std::unique_ptr<foxglove::CallbackQueue> _fetchAssetQueue;
955  std::unordered_set<std::string> _invalidParams;
956 };
957 
958 } // namespace foxglove_bridge
959 
XmlRpc::XmlRpcValue::size
int size() const
response
const std::string response
foxglove_bridge::FoxgloveBridge::hasCapability
bool hasCapability(const std::string &capability)
Definition: ros1_foxglove_bridge_nodelet.cpp:928
foxglove_bridge::SubscriptionsByClient
std::map< ConnectionHandle, ros::Subscriber, std::owner_less<> > SubscriptionsByClient
Definition: ros1_foxglove_bridge_nodelet.cpp:55
foxglove::isWhitelisted
bool isWhitelisted(const std::string &name, const std::vector< std::regex > &regexPatterns)
Definition: regex_utils.hpp:10
XmlRpc::XmlRpcValue::toXml
std::string toXml() const
foxglove_bridge::FoxgloveBridge::_advertisedTopics
std::unordered_map< foxglove::ChannelId, foxglove::ChannelWithoutId > _advertisedTopics
Definition: ros1_foxglove_bridge_nodelet.cpp:939
resource_retriever::MemoryResource::size
uint32_t size
foxglove::WebSocketLogLevel::Warn
@ Warn
ros::MessageEvent::getReceiptTime
ros::Time getReceiptTime() const
ros::AdvertiseOptions::topic
std::string topic
foxglove_bridge::GenericService::data
std::vector< uint8_t > data
Definition: generic_service.hpp:14
foxglove_bridge::ConnectionHandle
websocketpp::connection_hdl ConnectionHandle
Definition: ros1_foxglove_bridge_nodelet.cpp:53
foxglove::FOXGLOVE_BRIDGE_GIT_HASH
const char FOXGLOVE_BRIDGE_GIT_HASH[]
foxglove_bridge::FoxgloveBridge::_assetUriAllowlistPatterns
std::vector< std::regex > _assetUriAllowlistPatterns
Definition: ros1_foxglove_bridge_nodelet.cpp:937
ros::service::exists
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
ros::service::call
bool call(const std::string &service_name, MReq &req, MRes &res)
ros::XMLRPCManager::bind
bool bind(const std::string &function_name, const XMLRPCFunc &cb)
foxglove::ServerOptions::certfile
std::string certfile
Definition: server_interface.hpp:51
foxglove::ClientAdvertisement::topic
std::string topic
Definition: common.hpp:79
foxglove::ServerHandlers::subscribeConnectionGraphHandler
std::function< void(bool)> subscribeConnectionGraphHandler
Definition: server_interface.hpp:75
foxglove_bridge::FoxgloveBridge
Definition: ros1_foxglove_bridge_nodelet.cpp:60
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
foxglove::WebSocketLogLevel::Error
@ Error
foxglove_bridge::GenericService
Definition: generic_service.hpp:11
foxglove_bridge::FoxgloveBridge::clientAdvertise
void clientAdvertise(const foxglove::ClientAdvertisement &channel, ConnectionHandle clientHandle)
Definition: ros1_foxglove_bridge_nodelet.cpp:304
foxglove_bridge::FoxgloveBridge::_advertisedServices
std::unordered_map< foxglove::ServiceId, foxglove::ServiceWithoutId > _advertisedServices
Definition: ros1_foxglove_bridge_nodelet.cpp:941
foxglove::ClientChannelId
uint32_t ClientChannelId
Definition: common.hpp:27
XmlRpc::XmlRpcException::getMessage
const std::string & getMessage() const
foxglove::ServiceResponse::encoding
std::string encoding
Definition: common.hpp:133
foxglove_bridge::FoxgloveBridge::_updateCount
size_t _updateCount
Definition: ros1_foxglove_bridge_nodelet.cpp:948
foxglove_bridge::FoxgloveBridge::_serviceWhitelistPatterns
std::vector< std::regex > _serviceWhitelistPatterns
Definition: ros1_foxglove_bridge_nodelet.cpp:936
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
foxglove::ServerHandlers::clientMessageHandler
std::function< void(const ClientMessage &, ConnectionHandle)> clientMessageHandler
Definition: server_interface.hpp:64
foxglove_bridge::FoxgloveBridge::TopicAndDatatype
std::pair< std::string, std::string > TopicAndDatatype
Definition: ros2_foxglove_bridge.hpp:36
ros.h
foxglove_bridge::FoxgloveBridge::_fetchAssetQueue
std::unique_ptr< foxglove::CallbackQueue > _fetchAssetQueue
Definition: ros1_foxglove_bridge_nodelet.cpp:954
foxglove::ServiceResponse
Definition: common.hpp:130
foxglove_bridge::FoxgloveBridge::updateAdvertisedServices
void updateAdvertisedServices()
Definition: ros2_foxglove_bridge.cpp:290
foxglove::ServerHandlers::serviceRequestHandler
std::function< void(const ServiceRequest &, ConnectionHandle)> serviceRequestHandler
Definition: server_interface.hpp:74
foxglove_bridge::FoxgloveBridge::PairHash::operator()
std::size_t operator()(const std::pair< T1, T2 > &pair) const
Definition: ros1_foxglove_bridge_nodelet.cpp:211
resource_retriever
foxglove_bridge::FoxgloveBridge::FoxgloveBridge
FoxgloveBridge()=default
ros::Timer::stop
void stop()
resource_retriever::MemoryResource
foxglove::ServerHandlers::parameterChangeHandler
std::function< void(const std::vector< Parameter > &, const std::optional< std::string > &, ConnectionHandle)> parameterChangeHandler
Definition: server_interface.hpp:70
foxglove::ServiceWithoutId::responseSchema
std::string responseSchema
Definition: common.hpp:118
foxglove::ServiceWithoutId
Definition: common.hpp:114
ros::names::clean
ROSCPP_DECL std::string clean(const std::string &name)
foxglove_bridge::SUBSCRIPTION_QUEUE_LENGTH
constexpr uint32_t SUBSCRIPTION_QUEUE_LENGTH
Definition: ros1_foxglove_bridge_nodelet.cpp:47
foxglove::ServiceResponse::callId
uint32_t callId
Definition: common.hpp:132
foxglove::FetchAssetResponse
Definition: common.hpp:155
foxglove::CAPABILITY_TIME
constexpr char CAPABILITY_TIME[]
Definition: common.hpp:14
foxglove::ParameterSubscriptionOperation
ParameterSubscriptionOperation
Definition: parameter.hpp:11
foxglove::ServerOptions::supportedEncodings
std::vector< std::string > supportedEncodings
Definition: server_interface.hpp:47
foxglove_bridge::FoxgloveBridge::clientMessage
void clientMessage(const foxglove::ClientMessage &clientMsg, ConnectionHandle clientHandle)
Definition: ros1_foxglove_bridge_nodelet.cpp:392
foxglove::ParameterType
ParameterType
Definition: parameter.hpp:16
foxglove_bridge::DEFAULT_SERVICE_TYPE_RETRIEVAL_TIMEOUT_MS
constexpr int DEFAULT_SERVICE_TYPE_RETRIEVAL_TIMEOUT_MS
Definition: ros1_foxglove_bridge_nodelet.cpp:50
foxglove::ServerOptions::keyfile
std::string keyfile
Definition: server_interface.hpp:52
foxglove_bridge::FoxgloveBridge::updateAdvertisedServices
void updateAdvertisedServices(const std::vector< std::string > &serviceNames)
Definition: ros1_foxglove_bridge_nodelet.cpp:588
ros::XMLRPCManager::getServerURI
const std::string & getServerURI() const
foxglove_bridge::FoxgloveBridge::_subscribeGraphUpdates
std::atomic< bool > _subscribeGraphUpdates
Definition: ros1_foxglove_bridge_nodelet.cpp:953
foxglove_bridge::FoxgloveBridge::_subscriptions
std::unordered_map< foxglove::ChannelId, SubscriptionsByClient > _subscriptions
Definition: ros1_foxglove_bridge_nodelet.cpp:940
regex_utils.hpp
foxglove_bridge::FoxgloveBridge::subscribe
void subscribe(foxglove::ChannelId channelId, ConnectionHandle clientHandle)
Definition: ros1_foxglove_bridge_nodelet.cpp:216
foxglove_bridge::FoxgloveBridge::_capabilities
std::vector< std::string > _capabilities
Definition: ros1_foxglove_bridge_nodelet.cpp:951
foxglove_bridge::FoxgloveBridge::_publicationsMutex
std::shared_mutex _publicationsMutex
Definition: ros1_foxglove_bridge_nodelet.cpp:944
foxglove::ChannelWithoutId::topic
std::string topic
Definition: common.hpp:52
foxglove::ServerHandlers::fetchAssetHandler
std::function< void(const std::string &, uint32_t, ConnectionHandle)> fetchAssetHandler
Definition: server_interface.hpp:76
ros::AdvertiseOptions::datatype
std::string datatype
foxglove::ClientChannelError
Definition: server_interface.hpp:38
ros::AdvertiseOptions::has_header
bool has_header
foxglove_bridge::FoxgloveBridge::~FoxgloveBridge
virtual ~FoxgloveBridge()
Definition: ros1_foxglove_bridge_nodelet.cpp:201
ros::MessageEvent::getConstMessage
const boost::shared_ptr< ConstMessage > & getConstMessage() const
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
foxglove::ServerOptions::useCompression
bool useCompression
Definition: server_interface.hpp:54
foxglove_bridge::FoxgloveBridge::_maxUpdateMs
size_t _maxUpdateMs
Definition: ros1_foxglove_bridge_nodelet.cpp:947
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
foxglove::ServiceWithoutId::name
std::string name
Definition: common.hpp:115
ros::AdvertiseOptions
resource_retriever::MemoryResource::data
boost::shared_array< uint8_t > data
ros::ok
ROSCPP_DECL bool ok()
foxglove::ServiceResponse::data
std::vector< uint8_t > data
Definition: common.hpp:134
foxglove_bridge::FoxgloveBridge::_servicesMutex
std::shared_mutex _servicesMutex
Definition: ros1_foxglove_bridge_nodelet.cpp:945
foxglove::DEFAULT_SEND_BUFFER_LIMIT_BYTES
constexpr size_t DEFAULT_SEND_BUFFER_LIMIT_BYTES
Definition: server_interface.hpp:16
ros::names::resolve
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
foxglove::ServiceWithoutId::type
std::string type
Definition: common.hpp:116
foxglove_bridge::retrieveServiceType
std::string retrieveServiceType(const std::string &serviceName, std::chrono::milliseconds timeout_ms)
Definition: service_utils.cpp:24
foxglove_bridge::FoxgloveBridge::_clientAdvertisedTopics
PublicationsByClient _clientAdvertisedTopics
Definition: ros1_foxglove_bridge_nodelet.cpp:942
foxglove_bridge::PublicationsByClient
std::map< ConnectionHandle, ClientPublications, std::owner_less<> > PublicationsByClient
Definition: ros1_foxglove_bridge_nodelet.cpp:57
foxglove_bridge::FoxgloveBridge::_invalidParams
std::unordered_set< std::string > _invalidParams
Definition: ros1_foxglove_bridge_nodelet.cpp:955
foxglove::ServerHandlers::unsubscribeHandler
std::function< void(ChannelId, ConnectionHandle)> unsubscribeHandler
Definition: server_interface.hpp:61
class_list_macros.h
foxglove::ServerOptions::useTls
bool useTls
Definition: server_interface.hpp:50
foxglove::WebSocketLogLevel::Info
@ Info
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
foxglove_bridge::FoxgloveBridge::fetchAsset
void fetchAsset(const std::string &uri, uint32_t requestId, ConnectionHandle clientHandle)
Definition: ros1_foxglove_bridge_nodelet.cpp:897
foxglove::ConnHandle
websocketpp::connection_hdl ConnHandle
Definition: websocket_server.hpp:68
foxglove::ServerOptions
Definition: server_interface.hpp:45
foxglove_bridge::GenericService::md5sum
std::string md5sum
Definition: generic_service.hpp:13
foxglove_bridge::FoxgloveBridge::unsubscribe
void unsubscribe(foxglove::ChannelId channelId, ConnectionHandle clientHandle)
Definition: ros1_foxglove_bridge_nodelet.cpp:266
xmlrpc_manager.h
foxglove_bridge::FoxgloveBridge::updateAdvertisedTopicsAndServices
void updateAdvertisedTopicsAndServices(const ros::TimerEvent &)
Definition: ros1_foxglove_bridge_nodelet.cpp:426
foxglove::WebSocketUserAgent
const char * WebSocketUserAgent()
Definition: foxglove_bridge.cpp:7
foxglove::ClientAdvertisement::channelId
ClientChannelId channelId
Definition: common.hpp:78
foxglove::ChannelError
Definition: server_interface.hpp:35
foxglove_bridge::FoxgloveBridge::updateAdvertisedTopics
void updateAdvertisedTopics()
Definition: ros1_foxglove_bridge_nodelet.cpp:490
generic_service.hpp
foxglove::ServerHandlers
Definition: server_interface.hpp:59
foxglove::ParameterSubscriptionOperation::SUBSCRIBE
@ SUBSCRIBE
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
foxglove_bridge::DEFAULT_ADDRESS
constexpr char DEFAULT_ADDRESS[]
Definition: ros1_foxglove_bridge_nodelet.cpp:44
foxglove::WebSocketLogLevel
WebSocketLogLevel
Definition: common.hpp:43
foxglove::ServerHandlers::subscribeHandler
std::function< void(ChannelId, ConnectionHandle)> subscribeHandler
Definition: server_interface.hpp:60
foxglove_bridge::FoxgloveBridge::getParameters
void getParameters(const std::vector< std::string > &parameters, const std::optional< std::string > &requestId, ConnectionHandle hdl)
Definition: ros1_foxglove_bridge_nodelet.cpp:651
ros::AdvertiseOptions::latch
bool latch
foxglove_bridge::FoxgloveBridge::parameterUpdates
void parameterUpdates(XmlRpc::XmlRpcValue &params, XmlRpc::XmlRpcValue &result)
Definition: ros1_foxglove_bridge_nodelet.cpp:800
ROS_DEBUG
#define ROS_DEBUG(...)
foxglove_bridge::FoxgloveBridge::subscribeParameters
void subscribeParameters(const std::vector< std::string > &parameters, foxglove::ParameterSubscriptionOperation op, ConnectionHandle)
Definition: ros1_foxglove_bridge_nodelet.cpp:770
foxglove::DEFAULT_CAPABILITIES
constexpr std::array< const char *, 6 > DEFAULT_CAPABILITIES
Definition: common.hpp:21
foxglove_bridge::FoxgloveBridge::setParameters
void setParameters(const std::vector< foxglove::Parameter > &parameters, const std::optional< std::string > &requestId, ConnectionHandle hdl)
Definition: ros1_foxglove_bridge_nodelet.cpp:722
foxglove::ClientMessage::advertisement
ClientAdvertisement advertisement
Definition: common.hpp:89
ros::AdvertiseOptions::queue_size
uint32_t queue_size
foxglove::WebSocketLogLevel::Debug
@ Debug
foxglove_bridge
Definition: generic_service.hpp:9
server_factory.hpp
foxglove::ClientAdvertisement
Definition: common.hpp:77
foxglove::ServerOptions::sessionId
std::string sessionId
Definition: server_interface.hpp:53
foxglove_bridge::toRosParam
XmlRpc::XmlRpcValue toRosParam(const foxglove::ParameterValue &param)
Definition: ros1_foxglove_bridge/src/param_utils.cpp:43
foxglove::ClientMessage
Definition: common.hpp:85
foxglove_bridge::TopicAndDatatype
std::pair< std::string, std::string > TopicAndDatatype
Definition: ros1_foxglove_bridge_nodelet.cpp:54
foxglove_bridge::MIN_UPDATE_PERIOD_MS
constexpr double MIN_UPDATE_PERIOD_MS
Definition: ros1_foxglove_bridge_nodelet.cpp:48
ros::XMLRPCManager
service_utils.hpp
ros::XMLRPCManager::start
void start()
foxglove::ServiceResponse::serviceId
ServiceId serviceId
Definition: common.hpp:131
ROS_WARN
#define ROS_WARN(...)
resource_retriever::Retriever
foxglove_bridge::MAX_INVALID_PARAMS_TRACKED
constexpr int MAX_INVALID_PARAMS_TRACKED
Definition: ros1_foxglove_bridge_nodelet.cpp:51
foxglove_bridge::DEFAULT_PORT
constexpr int DEFAULT_PORT
Definition: ros1_foxglove_bridge_nodelet.cpp:43
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::TimerEvent
foxglove_bridge::FoxgloveBridge::serviceRequest
void serviceRequest(const foxglove::ServiceRequest &request, ConnectionHandle clientHandle)
Definition: ros1_foxglove_bridge_nodelet.cpp:852
ros::XMLRPCManager::shutdown
void shutdown()
foxglove::ChannelWithoutId
Definition: common.hpp:51
foxglove::ServerOptions::capabilities
std::vector< std::string > capabilities
Definition: server_interface.hpp:46
foxglove_bridge::GenericService::type
std::string type
Definition: generic_service.hpp:12
ROS_FATAL
#define ROS_FATAL(...)
ros::master::execute
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
foxglove_bridge::FoxgloveBridge::PairHash
Definition: ros1_foxglove_bridge_nodelet.cpp:209
XmlRpc::XmlRpcException
set
ROSCPP_DECL void set(const std::string &key, bool b)
foxglove_bridge::FoxgloveBridge::_serviceRetrievalTimeoutMs
int _serviceRetrievalTimeoutMs
Definition: ros1_foxglove_bridge_nodelet.cpp:952
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
foxglove_bridge::PUBLICATION_QUEUE_LENGTH
constexpr uint32_t PUBLICATION_QUEUE_LENGTH
Definition: ros1_foxglove_bridge_nodelet.cpp:49
foxglove::ServiceWithoutId::requestSchema
std::string requestSchema
Definition: common.hpp:117
foxglove::ClientAdvertisement::encoding
std::string encoding
Definition: common.hpp:80
foxglove_bridge::FoxgloveBridge::onInit
virtual void onInit()
Definition: ros1_foxglove_bridge_nodelet.cpp:63
foxglove_bridge::FoxgloveBridge::logHandler
void logHandler(foxglove::WebSocketLogLevel level, char const *msg)
Definition: ros1_foxglove_bridge_nodelet.cpp:824
foxglove::MapOfSets
std::unordered_map< std::string, std::unordered_set< std::string > > MapOfSets
Definition: server_interface.hpp:18
nodelet::Nodelet
foxglove::ClientAdvertisement::schemaName
std::string schemaName
Definition: common.hpp:81
foxglove_bridge::FoxgloveBridge::_subscriptionsMutex
std::mutex _subscriptionsMutex
Definition: ros1_foxglove_bridge_nodelet.cpp:943
foxglove::ServerHandlers::clientUnadvertiseHandler
std::function< void(ClientChannelId, ConnectionHandle)> clientUnadvertiseHandler
Definition: server_interface.hpp:63
foxglove_bridge::fromRosParam
foxglove::Parameter fromRosParam(const std::string &name, const XmlRpc::XmlRpcValue &value)
Definition: ros1_foxglove_bridge/src/param_utils.cpp:39
foxglove_bridge.hpp
nodelet.h
foxglove::ServerHandlers::parameterRequestHandler
std::function< void(const std::vector< std::string > &, const std::optional< std::string > &, ConnectionHandle)> parameterRequestHandler
Definition: server_interface.hpp:67
foxglove_bridge::FoxgloveBridge::_paramWhitelistPatterns
std::vector< std::regex > _paramWhitelistPatterns
Definition: ros1_foxglove_bridge_nodelet.cpp:935
retriever.h
foxglove_bridge::FoxgloveBridge::_updateTimer
ros::Timer _updateTimer
Definition: ros1_foxglove_bridge_nodelet.cpp:946
ROS_ERROR
#define ROS_ERROR(...)
datatype
const char * datatype()
TimeBase< Time, Duration >::toNSec
uint64_t toNSec() const
foxglove::ServerOptions::sendBufferLimitBytes
size_t sendBufferLimitBytes
Definition: server_interface.hpp:49
foxglove_bridge::ROS1_CHANNEL_ENCODING
constexpr char ROS1_CHANNEL_ENCODING[]
Definition: ros1_foxglove_bridge_nodelet.cpp:46
nodelet::Nodelet::getName
const std::string & getName() const
foxglove_bridge::FoxgloveBridge::_topicWhitelistPatterns
std::vector< std::regex > _topicWhitelistPatterns
Definition: ros1_foxglove_bridge_nodelet.cpp:934
foxglove_bridge::parseRegexPatterns
std::vector< std::regex > parseRegexPatterns(const std::vector< std::string > &strings)
Definition: ros1_foxglove_bridge/src/param_utils.cpp:75
foxglove::ServiceError
Definition: server_interface.hpp:41
getParamNames
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
foxglove_bridge::FoxgloveBridge::rosMessageHandler
void rosMessageHandler(const foxglove::ChannelId channelId, ConnectionHandle clientHandle, const ros::MessageEvent< ros_babel_fish::BabelFishMessage const > &msgEvent)
Definition: ros1_foxglove_bridge_nodelet.cpp:844
param
T param(const std::string &param_name, const T &default_val)
foxglove::ChannelId
uint32_t ChannelId
Definition: common.hpp:26
ros::AdvertiseOptions::md5sum
std::string md5sum
foxglove::FetchAssetStatus::Error
@ Error
foxglove_bridge::ClientPublications
std::unordered_map< foxglove::ClientChannelId, ros::Publisher > ClientPublications
Definition: ros1_foxglove_bridge_nodelet.cpp:56
foxglove_bridge::DEFAULT_MAX_UPDATE_MS
constexpr int DEFAULT_MAX_UPDATE_MS
Definition: ros1_foxglove_bridge_nodelet.cpp:45
websocket_server.hpp
foxglove::CAPABILITY_SERVICES
constexpr char CAPABILITY_SERVICES[]
Definition: common.hpp:17
ros::AdvertiseOptions::message_definition
std::string message_definition
foxglove::ServerHandlers::clientAdvertiseHandler
std::function< void(const ClientAdvertisement &, ConnectionHandle)> clientAdvertiseHandler
Definition: server_interface.hpp:62
foxglove_bridge::FoxgloveBridge::clientUnadvertise
void clientUnadvertise(foxglove::ClientChannelId channelId, ConnectionHandle clientHandle)
Definition: ros1_foxglove_bridge_nodelet.cpp:359
foxglove::FOXGLOVE_BRIDGE_VERSION
const char FOXGLOVE_BRIDGE_VERSION[]
foxglove::WebSocketLogLevel::Critical
@ Critical
foxglove::CAPABILITY_ASSETS
constexpr char CAPABILITY_ASSETS[]
Definition: common.hpp:19
ROS_INFO
#define ROS_INFO(...)
foxglove_bridge::FoxgloveBridge::_useSimTime
bool _useSimTime
Definition: ros1_foxglove_bridge_nodelet.cpp:950
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
message_event.h
ros::Timer
foxglove::ServerOptions::clientTopicWhitelistPatterns
std::vector< std::regex > clientTopicWhitelistPatterns
Definition: server_interface.hpp:55
foxglove_bridge::FoxgloveBridge::_server
std::unique_ptr< foxglove::ServerInterface< ConnectionHandle > > _server
Definition: ros1_foxglove_bridge_nodelet.cpp:932
foxglove::FetchAssetStatus::Success
@ Success
foxglove_bridge::FoxgloveBridge::xmlrpcServer
ros::XMLRPCManager xmlrpcServer
Definition: ros1_foxglove_bridge_nodelet.cpp:938
foxglove_bridge::FoxgloveBridge::_clockSubscription
ros::Subscriber _clockSubscription
Definition: ros1_foxglove_bridge_nodelet.cpp:949
XmlRpc::XmlRpcValue
foxglove::ServerOptions::metadata
std::unordered_map< std::string, std::string > metadata
Definition: server_interface.hpp:48
foxglove::ServerHandlers::parameterSubscriptionHandler
std::function< void(const std::vector< std::string > &, ParameterSubscriptionOperation, ConnectionHandle)> parameterSubscriptionHandler
Definition: server_interface.hpp:73
ros::MessageEvent
ros::Subscriber
nodelet::Nodelet::getMTNodeHandle
ros::NodeHandle & getMTNodeHandle() const
foxglove_bridge::FoxgloveBridge::_rosTypeInfoProvider
ros_babel_fish::IntegratedDescriptionProvider _rosTypeInfoProvider
Definition: ros1_foxglove_bridge_nodelet.cpp:933


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