Skip to content

Commit

Permalink
Stricter asset uri whitelist
Browse files Browse the repository at this point in the history
  • Loading branch information
achim-k committed Jul 6, 2023
1 parent 8c02db3 commit 903579e
Show file tree
Hide file tree
Showing 6 changed files with 9 additions and 8 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ Parameters are provided to configure the behavior of the bridge. These parameter
* __send_buffer_limit__: Connection send buffer limit in bytes. Messages will be dropped when a connection's send buffer reaches this limit to avoid a queue of outdated messages building up. Defaults to `10000000` (10 MB).
* __use_compression__: Use websocket compression (permessage-deflate). Suited for connections with smaller bandwith, at the cost of additional CPU load.
* __capabilities__: List of supported [server capabilities](https://github.com/foxglove/ws-protocol/blob/main/docs/spec.md). Defaults to `[clientPublish,parameters,parametersSubscribe,services,connectionGraph,assets]`.
* __asset_uri_whitelist__: List of regular expressions ([ECMAScript grammar](https://en.cppreference.com/w/cpp/regex/ecmascript)) of allowed asset URIs. Defaults to `["package://.*"]`.
* __asset_uri_whitelist__: List of regular expressions ([ECMAScript grammar](https://en.cppreference.com/w/cpp/regex/ecmascript)) of allowed asset URIs. Uses the [resource_retriever](https://index.ros.org/p/resource_retriever/github-ros-resource_retriever) to resolve `package://`, `file://` or `http(s)://` URIs. Note that this list should be carefully configured such that no secret files can be fetched. Defaults to `["package://(\w+/?)+\.(dae|stl|urdf|xacro)"]`.
* (ROS 1) __max_update_ms__: The maximum number of milliseconds to wait in between polling `roscore` for new topics, services, or parameters. Defaults to `5000`.
* (ROS 2) __num_threads__: The number of threads to use for the ROS node executor. This controls the number of subscriptions that can be processed in parallel. 0 means one thread per CPU core. Defaults to `0`.
* (ROS 2) __min_qos_depth__: Minimum depth used for the QoS profile of subscriptions. Defaults to `1`. This is to set a lower limit for a subscriber's QoS depth which is computed by summing up depths of all publishers. See also [#208](https://github.com/foxglove/ros-foxglove-bridge/issues/208).
Expand Down
2 changes: 1 addition & 1 deletion ros1_foxglove_bridge/launch/foxglove_bridge.launch
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
<arg name="nodelet_manager" default="foxglove_nodelet_manager" />
<arg name="num_threads" default="0" />
<arg name="capabilities" default="[clientPublish,parameters,parametersSubscribe,services,connectionGraph,assets]" />
<arg name="asset_uri_whitelist" default="['package://.*']" />
<arg name="asset_uri_whitelist" default="['package://(/?\w+)+\.(dae|stl|urdf|xacro)']" />

<node pkg="nodelet" type="nodelet" name="foxglove_nodelet_manager" args="manager"
if="$(eval nodelet_manager == 'foxglove_nodelet_manager')">
Expand Down
6 changes: 3 additions & 3 deletions ros1_foxglove_bridge/src/ros1_foxglove_bridge_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,8 +101,8 @@ class FoxgloveBridge : public nodelet::Nodelet {
ROS_ERROR("Failed to parse one or more service whitelist patterns");
}

const auto assetUriWhitelist =
nhp.param<std::vector<std::string>>("asset_uri_whitelist", {"package://.*", "file://.*"});
const auto assetUriWhitelist = nhp.param<std::vector<std::string>>(
"asset_uri_whitelist", {"package://(/?\\w+)+\\.(dae|stl|urdf|xacro)"});
_assetUriWhitelistPatterns = parseRegexPatterns(assetUriWhitelist);
if (assetUriWhitelist.size() != _assetUriWhitelistPatterns.size()) {
ROS_ERROR("Failed to parse one or more asset URI whitelist patterns");
Expand Down Expand Up @@ -873,7 +873,7 @@ class FoxgloveBridge : public nodelet::Nodelet {
response.errorMessage = "";
response.data.resize(memoryResource.size);
std::memcpy(response.data.data(), memoryResource.data.get(), memoryResource.size);
} catch (const resource_retriever::Exception& ex) {
} catch (const std::exception& ex) {
ROS_WARN("Failed to retrieve asset '%s': %s", uri.c_str(), ex.what());
response.status = foxglove::FetchAssetStatus::Error;
response.errorMessage = "Failed to retrieve asset " + uri;
Expand Down
2 changes: 1 addition & 1 deletion ros2_foxglove_bridge/launch/foxglove_bridge_launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
<arg name="use_sim_time" default="false" />
<arg name="capabilities" default="[clientPublish,parameters,parametersSubscribe,services,connectionGraph,assets]" />
<arg name="include_hidden" default="false" />
<arg name="asset_uri_whitelist" default="['package://.*']" />
<arg name="asset_uri_whitelist" default="['package://(\\w+/?)+\\.(dae|stl|urdf|xacro)']" /> <!-- Needs double-escape -->

<node pkg="foxglove_bridge" exec="foxglove_bridge">
<param name="port" value="$(var port)" />
Expand Down
3 changes: 2 additions & 1 deletion ros2_foxglove_bridge/src/param_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,8 @@ void declareParameters(rclcpp::Node* node) {
assetUriWhiteListDescription.description =
"List of regular expressions (ECMAScript) of whitelisted asset URIs.";
assetUriWhiteListDescription.read_only = true;
node->declare_parameter(PARAM_ASSET_URI_WHITELIST, std::vector<std::string>({"package://.*"}),
node->declare_parameter(PARAM_ASSET_URI_WHITELIST,
std::vector<std::string>({"package://(/?\\w+)+\\.(dae|stl|urdf|xacro)"}),
paramWhiteListDescription);
}

Expand Down
2 changes: 1 addition & 1 deletion ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -835,7 +835,7 @@ void FoxgloveBridge::fetchAsset(const std::string& uri, uint32_t requestId,
response.errorMessage = "";
response.data.resize(memoryResource.size);
std::memcpy(response.data.data(), memoryResource.data.get(), memoryResource.size);
} catch (const resource_retriever::Exception& ex) {
} catch (const std::exception& ex) {
RCLCPP_WARN(this->get_logger(), "Failed to retrieve asset '%s': %s", uri.c_str(), ex.what());
response.status = foxglove::FetchAssetStatus::Error;
response.errorMessage = "Failed to retrieve asset " + uri;
Expand Down

0 comments on commit 903579e

Please sign in to comment.