6 #include <shared_mutex>
8 #include <unordered_set>
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>
23 #include <foxglove_bridge/param_utils.hpp>
32 std::unordered_set<std::string>
set;
33 for (
int i = 0; i < v.
size(); ++i) {
65 const auto address = nhp.param<std::string>(
"address",
DEFAULT_ADDRESS);
67 const auto send_buffer_limit =
static_cast<size_t>(
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",
"");
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)));
82 const auto topicWhitelistPatterns =
83 nhp.param<std::vector<std::string>>(
"topic_whitelist", {
".*"});
86 ROS_ERROR(
"Failed to parse one or more topic whitelist patterns");
88 const auto paramWhitelist = nhp.param<std::vector<std::string>>(
"param_whitelist", {
".*"});
91 ROS_ERROR(
"Failed to parse one or more param whitelist patterns");
94 const auto serviceWhitelist = nhp.param<std::vector<std::string>>(
"service_whitelist", {
".*"});
97 ROS_ERROR(
"Failed to parse one or more service whitelist patterns");
100 const auto clientTopicWhitelist =
101 nhp.param<std::vector<std::string>>(
"client_topic_whitelist", {
".*"});
103 if (clientTopicWhitelist.size() != clientTopicWhitelistPatterns.size()) {
104 ROS_ERROR(
"Failed to parse one or more service whitelist patterns");
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)$"});
113 ROS_ERROR(
"Failed to parse one or more asset URI whitelist patterns");
116 const char* rosDistro = std::getenv(
"ROS_DISTRO");
117 ROS_INFO(
"Starting foxglove_bridge (%s, %s@%s) with %s", rosDistro,
128 serverOptions.
metadata = {{
"ROS_DISTRO", rosDistro}};
131 serverOptions.
useTls = useTLS;
133 serverOptions.
keyfile = keyfile;
143 _server = foxglove::ServerFactory::createServer<ConnectionHandle>(
"foxglove_bridge",
151 std::placeholders::_1, std::placeholders::_2);
153 std::placeholders::_1, std::placeholders::_2);
155 std::placeholders::_1, std::placeholders::_2);
158 std::placeholders::_2, std::placeholders::_3);
161 std::placeholders::_2, std::placeholders::_3);
164 std::placeholders::_2, std::placeholders::_3);
166 std::placeholders::_1, std::placeholders::_2);
179 _server->setHandlers(std::move(hdlrs));
181 _server->start(address,
static_cast<uint16_t
>(port));
184 std::placeholders::_1, std::placeholders::_2));
191 "/clock", 10, [&](
const rosgraph_msgs::Clock::ConstPtr msg) {
192 _server->broadcastTime(msg->clock.toNSec());
195 }
catch (
const std::exception& err) {
196 ROS_ERROR(
"Failed to start websocket server: %s", err.what());
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);
221 const std::string errMsg =
222 "Received subscribe request for unknown channel " + std::to_string(channelId);
227 const auto& channel = it->second;
228 const auto& topic = channel.topic;
229 const auto&
datatype = channel.schemaName;
232 auto [subscriptionsIt, firstSubscription] =
234 auto& subscriptionsByClient = subscriptionsIt->second;
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);
245 subscriptionsByClient.emplace(
246 clientHandle,
getMTNodeHandle().subscribe<ros_babel_fish::BabelFishMessage>(
249 std::placeholders::_1)));
250 if (firstSubscription) {
251 ROS_INFO(
"Subscribed to topic \"%s\" (%s) on channel %d", topic.c_str(),
datatype.c_str(),
255 ROS_INFO(
"Added subscriber #%zu to topic \"%s\" (%s) on channel %d",
256 subscriptionsByClient.size(), topic.c_str(),
datatype.c_str(), channelId);
258 }
catch (
const std::exception& ex) {
259 const std::string errMsg =
260 "Failed to subscribe to topic '" + topic +
"' (" +
datatype +
"): " + ex.what();
271 const std::string errMsg =
272 "Received unsubscribe request for unknown channel " + std::to_string(channelId);
276 const auto& channel = channelIt->second;
281 std::to_string(channelId) +
282 " that was not subscribed to ");
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");
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);
299 ROS_INFO(
"Removed one subscription from channel %d (%zu subscription(s) left)", channelId,
300 subscriptionsByClient.size());
309 "' encoding is supported at the moment.");
315 auto [clientPublicationsIt, isFirstPublication] =
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");
328 if (!msgDescription) {
330 channel.
channelId,
"Failed to retrieve type information of data type '" +
337 advertiseOptions.
latch =
false;
338 advertiseOptions.
md5sum = msgDescription->md5;
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(),
353 "Failed to create publisher for topic " + channel.
topic +
"(" + channel.
schemaName +
")";
365 channelId,
"Ignoring client unadvertisement from " +
366 _server->remoteEndpointString(clientHandle) +
" for unknown channel " +
367 std::to_string(channelId) +
", client has no advertised topics");
370 auto& clientPublications = clientPublicationsIt->second;
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)");
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);
387 if (clientPublications.empty()) {
393 ros_babel_fish::BabelFishMessage::Ptr msg(
new ros_babel_fish::BabelFishMessage);
394 msg->read(clientMsg);
402 channelId,
"Dropping client message from " +
_server->remoteEndpointString(clientHandle) +
403 " for unknown channel " + std::to_string(channelId) +
404 ", client has no advertised topics");
407 auto& clientPublications = clientPublicationsIt->second;
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)");
418 channelPublicationIt->second.publish(msg);
419 }
catch (
const std::exception& ex) {
421 channelPublicationIt->second.getTopic() +
435 std::vector<std::string> serviceNames;
439 if (querySystemState) {
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];
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]));
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]));
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]));
469 ROS_WARN(
"Failed to call getSystemState: %s", result.
toXml().c_str());
474 if (servicesEnabled) {
478 _server->updateConnectionGraph(publishers, subscribers, services);
484 const auto nextUpdateMs = std::max(
499 ROS_WARN(
"Failed to retrieve topics from ROS master.");
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];
511 latestTopics.emplace(topicName,
datatype);
515 if (
const auto numIgnoredTopics = topicNamesAndTypes.
size() - latestTopics.size()) {
517 "%zu topics have been ignored as they do not match any pattern on the topic whitelist",
524 std::vector<foxglove::ChannelId> channelIdsToRemove;
527 channelIt->second.schemaName};
528 if (latestTopics.find(topicAndDatatype) == latestTopics.end()) {
529 const auto channelId = channelIt->first;
530 channelIdsToRemove.push_back(channelId);
532 ROS_DEBUG(
"Removed channel %d for topic \"%s\" (%s)", channelId,
533 topicAndDatatype.first.c_str(), topicAndDatatype.second.c_str());
539 _server->removeChannels(channelIdsToRemove);
542 std::vector<foxglove::ChannelWithoutId> channelsToAdd;
543 for (
const auto& topicAndDatatype : latestTopics) {
545 [topicAndDatatype](
const auto& channelIdAndChannel) {
546 const auto& channel = channelIdAndChannel.second;
547 return channel.topic == topicAndDatatype.first &&
548 channel.schemaName == topicAndDatatype.second;
554 newChannel.
topic = topicAndDatatype.first;
555 newChannel.schemaName = topicAndDatatype.second;
559 const auto msgDescription =
561 if (msgDescription) {
562 newChannel.schema = msgDescription->message_definition;
564 ROS_WARN(
"Could not find definition for type %s", topicAndDatatype.second.c_str());
567 newChannel.schema =
"";
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());
575 channelsToAdd.push_back(newChannel);
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];
583 ROS_DEBUG(
"Advertising channel %d for topic \"%s\" (%s)", channelId, channel.topic.c_str(),
584 channel.schemaName.c_str());
592 std::vector<foxglove::ServiceId> servicesToRemove;
595 std::find_if(serviceNames.begin(), serviceNames.end(), [service](
const auto& serviceName) {
596 return serviceName == service.second.name;
598 if (it == serviceNames.end()) {
599 servicesToRemove.push_back(service.first);
602 for (
auto serviceId : servicesToRemove) {
605 _server->removeServices(servicesToRemove);
608 std::vector<foxglove::ServiceWithoutId> newServices;
609 for (
const auto& serviceName : serviceNames) {
611 [&serviceName](
const auto& idWithService) {
612 return idWithService.second.name == serviceName;
618 const auto serviceType =
623 service.
name = serviceName;
624 service.
type = serviceType;
626 if (srvDescription) {
627 service.
requestSchema = srvDescription->request->message_definition;
628 service.
responseSchema = srvDescription->response->message_definition;
630 ROS_ERROR(
"Failed to retrieve type information for service '%s' of type '%s'",
631 serviceName.c_str(), serviceType.c_str());
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());
645 const auto serviceIds =
_server->addServices(newServices);
646 for (
size_t i = 0; i < serviceIds.size(); ++i) {
653 const bool allParametersRequested = parameters.empty();
654 std::vector<std::string> parameterNames = parameters;
655 if (allParametersRequested) {
657 const auto errMsg =
"Failed to retrieve parameter names";
659 throw std::runtime_error(errMsg);
664 std::vector<foxglove::Parameter> params;
665 std::vector<std::string> invalidParams;
666 for (
const auto& paramName : parameterNames) {
668 if (allParametersRequested) {
671 ROS_ERROR(
"Parameter '%s' is not on the allowlist", paramName.c_str());
683 }
catch (
const std::exception& ex) {
684 ROS_ERROR(
"Invalid parameter '%s': %s", paramName.c_str(), ex.what());
685 invalidParams.push_back(paramName);
689 invalidParams.push_back(paramName);
692 ROS_ERROR(
"Invalid parameter '%s'", paramName.c_str());
693 invalidParams.push_back(paramName);
698 _server->publishParameterValues(hdl, params, requestId);
701 for (std::string&
param : invalidParams) {
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) {
715 throw std::runtime_error(errorMsg);
717 throw std::runtime_error(
"Failed to retrieve one or multiple parameters");
728 for (
const auto&
param : parameters) {
729 const auto paramName =
param.getName();
731 ROS_ERROR(
"Parameter '%s' is not on the allowlist", paramName.c_str());
737 const auto paramType =
param.getType();
738 const auto paramValue =
param.getValue();
739 if (paramType == ParameterType::PARAMETER_NOT_SET) {
740 nh.deleteParam(paramName);
742 nh.setParam(paramName,
toRosParam(paramValue));
744 }
catch (
const std::exception& ex) {
745 ROS_ERROR(
"Failed to set parameter '%s': %s", paramName.c_str(), ex.what());
751 ROS_ERROR(
"Failed to set parameter '%s'", paramName.c_str());
758 std::vector<std::string> parameterNames(parameters.size());
759 for (
size_t i = 0; i < parameters.size(); ++i) {
760 parameterNames[i] = parameters[i].getName();
766 throw std::runtime_error(
"Failed to set one or multiple parameters");
775 for (
const auto& paramName : parameters) {
777 ROS_ERROR(
"Parameter '%s' is not allowlist", paramName.c_str());
786 const std::string opName = std::string(opVerb) +
"Param";
788 ROS_DEBUG(
"%s '%s'", opName.c_str(), paramName.c_str());
790 ROS_WARN(
"Failed to %s '%s': %s", opVerb, paramName.c_str(), result.
toXml().c_str());
796 throw std::runtime_error(
"Failed to " + std::string(opVerb) +
" one or multiple parameters.");
802 result[1] = std::string(
"");
805 if (params.
size() != 3) {
806 ROS_ERROR(
"Parameter update called with invalid parameter size: %d", params.
size());
815 }
catch (
const std::exception& ex) {
816 ROS_ERROR(
"Failed to update parameter: %s", ex.what());
849 _server->sendMessage(clientHandle, channelId, receiptTimeNs, msg->buffer(), msg->size());
857 "Service with id " + std::to_string(request.
serviceId) +
" does not exist";
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());
868 "Service '" + serviceName +
"' does not exist");
872 if (!srvDescription) {
874 "Failed to retrieve type information for service " + serviceName +
"(" + serviceType +
")";
880 genReq.
type = genRes.
type = serviceType;
890 _server->sendServiceResponse(clientHandle, res);
893 request.
serviceId,
"Failed to call service " + serviceName +
"(" + serviceType +
")");
908 throw std::runtime_error(
"Asset URI not allowed: " + uri);
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;
932 std::unique_ptr<foxglove::ServerInterface<ConnectionHandle>>
_server;