diff --git a/geometry/BUILD.bazel b/geometry/BUILD.bazel index 04c30ae26104..fd7650bf944f 100644 --- a/geometry/BUILD.bazel +++ b/geometry/BUILD.bazel @@ -2,10 +2,15 @@ load( "@drake//tools/skylark:drake_cc.bzl", + "drake_cc_binary", "drake_cc_googletest", "drake_cc_library", "drake_cc_package_library", ) +load( + "@drake//tools/skylark:drake_py.bzl", + "drake_py_binary", +) load("//tools/lint:lint.bzl", "add_lint_tests") package(default_visibility = ["//visibility:public"]) @@ -30,6 +35,7 @@ drake_cc_package_library( ":geometry_version", ":internal_frame", ":internal_geometry", + ":meshcat", ":proximity_engine", ":proximity_properties", ":rgba", @@ -336,6 +342,45 @@ drake_cc_library( ], ) +drake_cc_library( + name = "meshcat", + srcs = ["meshcat.cc"], + hdrs = ["meshcat.h"], + data = [ + "//doc:favicon", + "@meshcat//:dist/index.html", + "@meshcat//:dist/main.min.js", + ], + deps = [ + "//common:essential", + "//common:find_resource", + "//common:unused", + "@msgpack", + "@uwebsockets", + ], +) + +drake_cc_binary( + name = "meshcat_manual_test", + testonly = True, + srcs = ["test/meshcat_manual_test.cc"], + visibility = ["//visibility:private"], + deps = [":meshcat"], +) + +drake_py_binary( + name = "meshcat_websocket_client", + testonly = True, + srcs = ["test/meshcat_websocket_client.py"], + visibility = ["//visibility:private"], +) + +drake_cc_googletest( + name = "meshcat_test", + data = [":meshcat_websocket_client"], + deps = [":meshcat"], +) + # ----------------------------------------------------- filegroup( diff --git a/geometry/dev/BUILD.bazel b/geometry/dev/BUILD.bazel deleted file mode 100644 index 317ac116b3cb..000000000000 --- a/geometry/dev/BUILD.bazel +++ /dev/null @@ -1,36 +0,0 @@ -# -*- python -*- - -load( - "@drake//tools/skylark:drake_cc.bzl", - "drake_cc_binary", - "drake_cc_library", -) -load("//tools/lint:lint.bzl", "add_lint_tests") - -package(default_visibility = ["//visibility:private"]) - -drake_cc_library( - name = "meshcat", - srcs = ["meshcat.cc"], - hdrs = ["meshcat.h"], - data = [ - "//doc:favicon", - "@meshcat//:dist/index.html", - "@meshcat//:dist/main.min.js", - ], - deps = [ - "//common:essential", - "//common:find_resource", - "//common:unused", - "@msgpack", - "@uwebsockets", - ], -) - -drake_cc_binary( - name = "meshcat_demo", - srcs = ["meshcat_demo.cc"], - deps = ["meshcat"], -) - -add_lint_tests() diff --git a/geometry/dev/meshcat.cc b/geometry/dev/meshcat.cc deleted file mode 100644 index 8b1faf51273c..000000000000 --- a/geometry/dev/meshcat.cc +++ /dev/null @@ -1,178 +0,0 @@ -#include "drake/geometry/dev/meshcat.h" - -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include "drake/common/find_resource.h" -#include "drake/common/never_destroyed.h" -#include "drake/common/unused.h" - -namespace { -std::string LoadFile(const std::string& filename) { - const std::string resource = drake::FindResourceOrThrow(filename); - std::ifstream file(resource.c_str(), std::ios::in); - if (!file.is_open()) - throw std::runtime_error("Error opening file: " + filename); - std::stringstream content; - content << file.rdbuf(); - file.close(); - return content.str(); -} -} // namespace - -namespace drake { -namespace geometry { - -namespace { - -constexpr static bool SSL = false; -struct PerSocketData { - // Intentionally left empty. -}; -using WebSocket = uWS::WebSocket; - -} // namespace - -class Meshcat::WebSocketPublisher { - public: - DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(WebSocketPublisher); - - WebSocketPublisher() : app_future(app_promise.get_future()) {} - - // Call this from websocket thread. - void SetAppPromise(uWS::App* app, uWS::Loop* loop) { - app_promise.set_value(std::make_pair(app, loop)); - } - - // Call this from main thread. - void GetAppFuture() { - std::tie(app_, loop_) = app_future.get(); - } - - template - void SetProperty(const std::string& path, const std::string& property, - const T& value) { - DRAKE_ASSERT(app_ != nullptr); - DRAKE_ASSERT(loop_ != nullptr); - - std::stringstream message; - - msgpack::zone z; - msgpack::pack(message, std::unordered_map( - {{"type", msgpack::object("set_property", z)}, - {"path", msgpack::object(path, z)}, - {"property", msgpack::object(property, z)}, - {"value", msgpack::object(value, z)}})); - - // Note: Must pass path and property by value because they will go out of - // scope. - loop_->defer([this, path, property, msg = message.str()]() { - app_->publish("all", msg, uWS::OpCode::BINARY, false); - set_properties_[path + "/" + property] = msg; - }); - } - - void SendTree(WebSocket* ws) { - // TODO(russt): Generalize this to publishing the entire scene tree. - for (const auto& [key, msg] : set_properties_) { - unused(key); - ws->send(msg); - } - } - - private: - std::promise> app_promise{}; - std::future> app_future{}; - - // Only loop_->defer() should be called from outside the websocket_thread. See - // the documentation for uWebSockets for further details: - // https://github.com/uNetworking/uWebSockets/blob/d94bf2cd43bed5e0de396a8412f156e15c141e98/misc/READMORE.md#threading - uWS::Loop* loop_{nullptr}; - - // The remaining variables should only be accessed from the websocket_thread. - uWS::App* app_{nullptr}; - std::unordered_map set_properties_{}; -}; - -Meshcat::Meshcat() { - // A std::promise is made in the WebSocketPublisher. - publisher_ = std::make_unique(); - websocket_thread_ = std::thread(&Meshcat::WebsocketMain, this); - // The std::promise is full-filled in WebsocketMain; we wait here to obtain - // that value. - publisher_->GetAppFuture(); -} - -Meshcat::~Meshcat() = default; - -void Meshcat::JoinWebSocketThread() { websocket_thread_.join(); } - -void Meshcat::SetProperty(const std::string& path, const std::string& property, - bool value) { - publisher_->SetProperty(path, property, value); -} - -void Meshcat::WebsocketMain() { - // Preload the three files we will serve (always). - static const drake::never_destroyed index_html( - LoadFile("drake/external/meshcat/dist/index.html")); - static const drake::never_destroyed main_min_js( - LoadFile("drake/external/meshcat/dist/main.min.js")); - static const drake::never_destroyed favicon_ico( - LoadFile("drake/doc/favicon.ico")); - int port = 7001; - const int kMaxPort = 7099; - - uWS::App::WebSocketBehavior behavior; - behavior.open = [this](WebSocket* ws) { - ws->subscribe("all"); - // Update this new connection with previously published data. - publisher_->SendTree(ws); - }; - - uWS::App app = - uWS::App() - .get("/*", - [&](uWS::HttpResponse* res, uWS::HttpRequest* req) { - if (req->getUrl() == "/main.min.js") { - res->end(main_min_js.access()); - } else if (req->getUrl() == "/favicon.ico") { - res->end(favicon_ico.access()); - } else { - res->end(index_html.access()); - } - }) - .ws("/*", std::move(behavior)); - - bool listening = false; - do { - app.listen( - port, LIBUS_LISTEN_EXCLUSIVE_PORT, - [port, &listening](us_listen_socket_t* listenSocket) { - if (listenSocket) { - std::cout - << "Meshcat listening for connections at http://127.0.0.1:" - << port << std::endl; - listening = true; - } - }); - } while (!listening && port++ <= kMaxPort); - - publisher_->SetAppPromise(&app, uWS::Loop::get()); - - app.run(); - - // run() should not terminate. If it does, then we've failed. - throw std::runtime_error("Meshcat websocket thread failed"); -} - -} // namespace geometry -} // namespace drake diff --git a/geometry/dev/meshcat_demo.cc b/geometry/dev/meshcat_demo.cc deleted file mode 100644 index fb624d9be60d..000000000000 --- a/geometry/dev/meshcat_demo.cc +++ /dev/null @@ -1,32 +0,0 @@ -#include "drake/geometry/dev/meshcat.h" - -/** This binary provides a simple demonstration of using Meshcat. It serves as -a stand-in for the proper test suite that will come in the next PR, since it -requires it's own substantial changes to the build system. - -To test, you must manually run `bazel run //geometry/dev:meshcat_demo`. It will -print two URLs to console. Navigating your browser to the first, you should see -that the normally blue meshcat background is not visible (the background will -look white). In the second URL, you should see the default meshcat view, but -the grid that normally shows the ground plane is not visible. -*/ - -int main() { - drake::geometry::Meshcat meshcat; - - // Note: this will only send one message to any new server. - meshcat.SetProperty("/Background", "visible", false); - meshcat.SetProperty("/Background", "visible", true); - meshcat.SetProperty("/Background", "visible", false); - - // Demonstrate that we can construct multiple meshcats (and they will serve on - // different ports). - drake::geometry::Meshcat meshcat2; - meshcat2.SetProperty("/Grid", "visible", false); - - // Effectively sleep forever. - meshcat.JoinWebSocketThread(); - meshcat2.JoinWebSocketThread(); - - return 0; -} diff --git a/geometry/meshcat.cc b/geometry/meshcat.cc new file mode 100644 index 000000000000..b2f07278af44 --- /dev/null +++ b/geometry/meshcat.cc @@ -0,0 +1,235 @@ +#include "drake/geometry/meshcat.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "drake/common/find_resource.h" +#include "drake/common/never_destroyed.h" +#include "drake/common/text_logging.h" +#include "drake/common/unused.h" + +namespace { +std::string LoadResource(const std::string& resource_name) { + const std::string resource = drake::FindResourceOrThrow(resource_name); + std::ifstream file(resource.c_str(), std::ios::in); + if (!file.is_open()) + throw std::runtime_error("Error opening resource: " + resource_name); + std::stringstream content; + content << file.rdbuf(); + file.close(); + return content.str(); +} + +const std::string& GetUrlContent(std::string_view url_path) { + static const drake::never_destroyed main_min_js( + LoadResource("drake/external/meshcat/dist/main.min.js")); + static const drake::never_destroyed favicon_ico( + LoadResource("drake/doc/favicon.ico")); + static const drake::never_destroyed index_html( + LoadResource("drake/external/meshcat/dist/index.html")); + if (url_path == "/main.min.js") { + return main_min_js.access(); + } + if (url_path == "/favicon.ico") { + return favicon_ico.access(); + } + return index_html.access(); +} + +} // namespace + +namespace drake { +namespace geometry { + +namespace { + +constexpr static bool SSL = false; +struct PerSocketData { + // Intentionally left empty. +}; +using WebSocket = uWS::WebSocket; + +} // namespace + +class Meshcat::WebSocketPublisher { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(WebSocketPublisher); + + WebSocketPublisher() + : main_thread_id_(std::this_thread::get_id()), + app_future_(app_promise_.get_future()) {} + + void SetWebSocketThreadId(std::thread::id id) { + websocket_thread_id_ = id; + } + + // Call this from websocket thread. + void SetAppPromise(uWS::App* app, uWS::Loop* loop, int port, + us_listen_socket_t* listen_socket) { + DRAKE_DEMAND(std::this_thread::get_id() == websocket_thread_id_); + app_promise_.set_value(std::make_tuple(app, loop, port, listen_socket)); + } + + // Call this from main thread. + void GetAppFuture() { + DRAKE_DEMAND(std::this_thread::get_id() == main_thread_id_); + std::tie(app_, loop_, port_, listen_socket_) = app_future_.get(); + } + + int port() const { + DRAKE_DEMAND(std::this_thread::get_id() == main_thread_id_); + DRAKE_DEMAND(port_ > 0); + return port_; + } + + template + void SetProperty(std::string_view path, std::string_view property, + const T& value) { + DRAKE_DEMAND(app_ != nullptr); + DRAKE_DEMAND(loop_ != nullptr); + DRAKE_DEMAND(std::this_thread::get_id() == main_thread_id_); + + std::stringstream message; + + msgpack::zone z; + msgpack::pack(message, std::map( + {{"type", msgpack::object("set_property", z)}, + {"path", msgpack::object(path, z)}, + {"property", msgpack::object(property, z)}, + {"value", msgpack::object(value, z)}})); + + // Note: Must pass path and property by value because they will go out of + // scope. + loop_->defer([this, path, property, msg = message.str()]() { + app_->publish("all", msg, uWS::OpCode::BINARY, false); + set_properties_[fmt::format("{}/{}", path, property)] = msg; + }); + } + + void SendTree(WebSocket* ws) { + DRAKE_DEMAND(std::this_thread::get_id() == websocket_thread_id_); + // TODO(russt): Generalize this to publishing the entire scene tree. + for (const auto& [key, msg] : set_properties_) { + unused(key); + ws->send(msg); + } + } + + void StartShutdown() { + DRAKE_DEMAND(std::this_thread::get_id() == main_thread_id_); + // Pass by value. + loop_->defer([socket = listen_socket_]() { + us_listen_socket_close(0, socket); + }); + } + + private: + std::promise> + app_promise_{}; + + // These variables should only be accessed in the main thread. + std::thread::id main_thread_id_{}; + std::future> + app_future_{}; + int port_{-1}; + us_listen_socket_t* listen_socket_{nullptr}; + + // These variables should only be accessed in the websocket thread. + std::thread::id websocket_thread_id_{}; + uWS::App* app_{nullptr}; + std::map set_properties_{}; + + // Only loop_->defer() should be called from outside the websocket_thread. See + // the documentation for uWebSockets for further details: + // https://github.com/uNetworking/uWebSockets/blob/d94bf2cd43bed5e0de396a8412f156e15c141e98/misc/READMORE.md#threading + uWS::Loop* loop_{nullptr}; +}; + +Meshcat::Meshcat() { + // A std::promise is made in the WebSocketPublisher. + publisher_ = std::make_unique(); + websocket_thread_ = std::thread(&Meshcat::WebsocketMain, this); + // The std::promise is full-filled in WebsocketMain; we wait here to obtain + // that value. + publisher_->GetAppFuture(); +} + +Meshcat::~Meshcat() { + publisher_->StartShutdown(); + websocket_thread_.join(); +} + +std::string Meshcat::web_url() const { + return fmt::format("http://localhost:{}", publisher_->port()); +} + +std::string Meshcat::ws_url() const { + return fmt::format("ws://localhost:{}", publisher_->port()); +} + +void Meshcat::JoinWebSocketThread() { websocket_thread_.join(); } + +void Meshcat::SetProperty(std::string_view path, std::string_view property, + bool value) { + publisher_->SetProperty(path, property, value); +} + +void Meshcat::WebsocketMain() { + publisher_->SetWebSocketThreadId(std::this_thread::get_id()); + + int port = 7001; + const int kMaxPort = 7099; + + uWS::App::WebSocketBehavior behavior; + behavior.open = [this](WebSocket* ws) { + ws->subscribe("all"); + // Update this new connection with previously published data. + publisher_->SendTree(ws); + }; + + // Fetch the index once to be sure that we preload the content. + GetUrlContent("/"); + + uWS::App app = + uWS::App() + .get("/*", + [&](uWS::HttpResponse* res, uWS::HttpRequest* req) { + res->end(GetUrlContent(req->getUrl())); + }) + .ws("/*", std::move(behavior)); + + us_listen_socket_t* listen_socket = nullptr; + do { + app.listen( + port, LIBUS_LISTEN_EXCLUSIVE_PORT, + [port, &listen_socket](us_listen_socket_t* socket) { + if (socket) { + drake::log()->info( + "Meshcat listening for connections at http://localhost:{}", + port); + listen_socket = socket; + } + }); + } while (listen_socket == nullptr && port++ < kMaxPort); + + if (listen_socket == nullptr) { + throw std::runtime_error("Meshcat failed to open a websocket port."); + } + + publisher_->SetAppPromise(&app, uWS::Loop::get(), port, listen_socket); + + app.run(); +} + +} // namespace geometry +} // namespace drake diff --git a/geometry/dev/meshcat.h b/geometry/meshcat.h similarity index 77% rename from geometry/dev/meshcat.h rename to geometry/meshcat.h index 3a3c8218e35e..8c4b54b91b8b 100644 --- a/geometry/dev/meshcat.h +++ b/geometry/meshcat.h @@ -18,8 +18,8 @@ this server is running. Note: This code is currently a skeleton implementation; it only allows you to set (boolean) properties as a minimal demonstration of sending data from C++ to -the viewer. It is the result of the first PR in a train of PRs that will -establish the full Meshcat functionality. See #13038. +the viewer. It is the result of the second PR in a train of PRs that will +establish the full Meshcat functionality. See #13038. */ class Meshcat { public: @@ -31,6 +31,13 @@ class Meshcat { ~Meshcat(); + /** Returns the hosted http URL. */ + std::string web_url() const; + + /** (Advanced) Returns the ws:// URL for direct connection to the websocket + interface. Most users should connect via a browser opened to web_url(). */ + std::string ws_url() const; + /** The thread run by this class will run for the lifetime of the Meshcat instance. We provide this method as a simple way to block the main thread to allow users to open their browser and work with the Meshcat scene. */ @@ -41,7 +48,7 @@ class Meshcat { meshcat.SetProperty("/Background", "visible", false); @endverbatim will turn off the background. */ - void SetProperty(const std::string& path, const std::string& property, + void SetProperty(std::string_view path, std::string_view property, bool value); private: diff --git a/geometry/test/meshcat_manual_test.cc b/geometry/test/meshcat_manual_test.cc new file mode 100644 index 000000000000..cf7fff5807a6 --- /dev/null +++ b/geometry/test/meshcat_manual_test.cc @@ -0,0 +1,28 @@ +#include "drake/geometry/meshcat.h" + +/** To test, you must manually run `bazel run //geometry:meshcat_manual_test`. +It will print two URLs to console. Navigating your browser to the first, you +should see that the normally blue meshcat background is not visible (the +background will look white). In the second URL, you should see the default +meshcat view, but the grid that normally shows the ground plane is not visible. +*/ + +int main() { + drake::geometry::Meshcat meshcat; + + // Note: this will only send one message to any new server. + meshcat.SetProperty("/Background", "visible", false); + meshcat.SetProperty("/Background", "visible", true); + meshcat.SetProperty("/Background", "visible", false); + + // Demonstrate that we can construct multiple meshcats (and they will serve on + // different ports). + drake::geometry::Meshcat meshcat2; + meshcat2.SetProperty("/Grid", "visible", false); + + // Effectively sleep forever. + meshcat.JoinWebSocketThread(); + meshcat2.JoinWebSocketThread(); + + return 0; +} diff --git a/geometry/test/meshcat_test.cc b/geometry/test/meshcat_test.cc new file mode 100644 index 000000000000..815cf427e127 --- /dev/null +++ b/geometry/test/meshcat_test.cc @@ -0,0 +1,92 @@ +#include "drake/geometry/meshcat.h" + +#include + +#include +#include +#include + +#include "drake/common/find_resource.h" + +namespace drake { +namespace geometry { +namespace { + +using ::testing::HasSubstr; + +// A small wrapper around std::system to ensure correct argument passing. +int SystemCall(const std::vector& argv) { + std::string command; + for (const std::string& arg : argv) { + // Note: Can't use ASSERT_THAT inside this subroutine. + EXPECT_THAT(arg, ::testing::Not(::testing::HasSubstr("'"))); + command = std::move(command) + "'" + arg + "' "; + } + return std::system(command.c_str()); +} + +GTEST_TEST(MeshcatTest, TestHttp) { + drake::geometry::Meshcat meshcat; + // Note: The server doesn't respect all requests; unfortunately we can't use + // curl --head and wget --spider nor curl --range to avoid downloading the + // full file. + EXPECT_EQ(SystemCall({"/usr/bin/curl", "-o", "/dev/null", "--silent", + meshcat.web_url() + "/index.html"}), + 0); + EXPECT_EQ(SystemCall({"/usr/bin/curl", "-o", "/dev/null", "--silent", + meshcat.web_url() + "/main.min.js"}), + 0); + EXPECT_EQ(SystemCall({"/usr/bin/curl", "-o", "/dev/null", "--silent", + meshcat.web_url() + "/favicon.ico"}), + 0); +} + +GTEST_TEST(MeshcatTest, ConstructMultiple) { + drake::geometry::Meshcat meshcat; + drake::geometry::Meshcat meshcat2; + + EXPECT_THAT(meshcat.web_url(), HasSubstr("http://localhost:")); + EXPECT_THAT(meshcat.ws_url(), HasSubstr("ws://localhost:")); + EXPECT_THAT(meshcat2.web_url(), HasSubstr("http://localhost:")); + EXPECT_THAT(meshcat2.ws_url(), HasSubstr("ws://localhost:")); + EXPECT_NE(meshcat.web_url(), meshcat2.web_url()); +} + +void CheckCommand(const drake::geometry::Meshcat& meshcat, int message_num, + const std::string& desired_command_json) { + EXPECT_EQ(SystemCall( + {FindResourceOrThrow("drake/geometry/meshcat_websocket_client"), + meshcat.ws_url(), std::to_string(message_num), + desired_command_json}), + 0); +} + +GTEST_TEST(MeshcatTest, SetProperty) { + drake::geometry::Meshcat meshcat; + meshcat.SetProperty("/Background", "visible", false); + CheckCommand(meshcat, 1, R"""({ + "property": "visible", + "value": false, + "path": "/Background", + "type": "set_property" + })"""); + meshcat.SetProperty("/Grid", "visible", false); + // Note: The order of the messages is due to "/Background" < "/Grid" in the + // std::map, not due to the order that SetProperty was called. + CheckCommand(meshcat, 1, R"""({ + "property": "visible", + "value": false, + "path": "/Background", + "type": "set_property" + })"""); + CheckCommand(meshcat, 2, R"""({ + "property": "visible", + "value": false, + "path": "/Grid", + "type": "set_property" + })"""); +} + +} // namespace +} // namespace geometry +} // namespace drake diff --git a/geometry/test/meshcat_websocket_client.py b/geometry/test/meshcat_websocket_client.py new file mode 100644 index 000000000000..479b81a03ec3 --- /dev/null +++ b/geometry/test/meshcat_websocket_client.py @@ -0,0 +1,45 @@ +# Test utility for Meshcat websockets (see the argparse for details). + +import argparse +import asyncio +import json +import sys +import umsgpack +import websockets + + +async def check_command(ws_url, message_number, desired_command): + async with websockets.connect(ws_url) as websocket: + message = '' + for n in range(message_number): + message = await asyncio.wait_for(websocket.recv(), timeout=10) + command = umsgpack.unpackb(message) + if command != desired_command: + print("FAILED") + print(f"Expected: {desired_command}") + print(f"Received: {command}") + sys.exit(1) + + +assert __name__ == "__main__" + +parser = argparse.ArgumentParser( + description="Test utility for Meshcat websockets") +parser.add_argument("ws_url", type=str, help="websocket URL") +parser.add_argument( + "message_number", + type=int, + help="number of messages to receive") +parser.add_argument( + "desired_command_json", + type=str, + help="the last message will be unpacked (to a dictionary) and compared to " + + "this desired value (specified as a json string)" +) +args = parser.parse_args() + +asyncio.get_event_loop().run_until_complete( + check_command(args.ws_url, args.message_number, + json.loads(args.desired_command_json))) + +sys.exit(0) diff --git a/setup/mac/source_distribution/requirements-test-only.txt b/setup/mac/source_distribution/requirements-test-only.txt index 24aeb80de266..1aae4684c687 100644 --- a/setup/mac/source_distribution/requirements-test-only.txt +++ b/setup/mac/source_distribution/requirements-test-only.txt @@ -1,3 +1,4 @@ jupyter pandas six +websockets diff --git a/setup/ubuntu/source_distribution/packages-bionic-test-only.txt b/setup/ubuntu/source_distribution/packages-bionic-test-only.txt index 7506d0ebe291..a066219718bb 100644 --- a/setup/ubuntu/source_distribution/packages-bionic-test-only.txt +++ b/setup/ubuntu/source_distribution/packages-bionic-test-only.txt @@ -1,3 +1,4 @@ +curl libstdc++6-7-dbg llvm-9 python3-dateutil @@ -15,6 +16,7 @@ python3-scipy-dbg python3-six python3-tk-dbg python3-uritemplate +python3-websockets python3-yaml-dbg python3-zmq-dbg valgrind diff --git a/setup/ubuntu/source_distribution/packages-focal-test-only.txt b/setup/ubuntu/source_distribution/packages-focal-test-only.txt index dc467c8034df..6bdfbfad5157 100644 --- a/setup/ubuntu/source_distribution/packages-focal-test-only.txt +++ b/setup/ubuntu/source_distribution/packages-focal-test-only.txt @@ -1,3 +1,4 @@ +curl kcov libstdc++6-10-dbg llvm-9 @@ -16,6 +17,7 @@ python3-scipy-dbg python3-six python3-tk-dbg python3-uritemplate +python3-websockets python3-yaml-dbg python3-zmq-dbg valgrind diff --git a/tools/workspace/meshcat/README.md b/tools/workspace/meshcat/README.md index 7c31b0b1b4c8..966e603b9333 100644 --- a/tools/workspace/meshcat/README.md +++ b/tools/workspace/meshcat/README.md @@ -8,6 +8,10 @@ is also required. The local testing consists largely of informal prodding: run an application which exercises meshcat and confirm that is reasonably well behaved. +Required: + - drake/geometry:meshcat_manual_test + - See the documentation at the top of that file for the expected behavior. + Possible options: - drake/manipulation/util/show_model.py