Skip to content

Commit

Permalink
[geometry] Establishes Meshcat in C++ (step 2)
Browse files Browse the repository at this point in the history
Adds test coverage, and therefore moves Meshcat out of dev.

Per discussion with jwnimmer-tri, the strategy here is to provide a reasonable coverage of the c++ code (CI runs most all of the code and verifies it doesn't segfault).

I explored more elaborate testing mechanisms (documented in #13038) using nodejs.  This could add value downstream, but adding nodejs support to bazel might be a big upfront (and even maintenance) cost for relatively small gain.  As jwnimmer-tri points out, we don't provide that level of coverage for DrakeVisualizer.
  • Loading branch information
RussTedrake committed Aug 19, 2021
1 parent 37fd417 commit e2ad0db
Show file tree
Hide file tree
Showing 11 changed files with 228 additions and 60 deletions.
42 changes: 42 additions & 0 deletions geometry/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -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"])
Expand All @@ -30,6 +35,7 @@ drake_cc_package_library(
":geometry_version",
":internal_frame",
":internal_geometry",
":meshcat",
":proximity_engine",
":proximity_properties",
":rgba",
Expand Down Expand Up @@ -336,6 +342,42 @@ 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_demo",
srcs = ["meshcat_demo.cc"],
deps = ["meshcat"],
)

drake_py_binary(
name = "meshcat_websocket_client",
srcs = ["test/meshcat_websocket_client.py"],
)

drake_cc_googletest(
name = "meshcat_test",
data = ["meshcat_websocket_client"],
tags = ["requires-network"],
deps = ["meshcat"],
)

# -----------------------------------------------------

filegroup(
Expand Down
36 changes: 0 additions & 36 deletions geometry/dev/BUILD.bazel

This file was deleted.

67 changes: 47 additions & 20 deletions geometry/dev/meshcat.cc → geometry/meshcat.cc
Original file line number Diff line number Diff line change
@@ -1,14 +1,16 @@
#include "drake/geometry/dev/meshcat.h"
#include "drake/geometry/meshcat.h"

#include <fstream>
#include <future>
#include <map>
#include <sstream>
#include <string>
#include <thread>
#include <unordered_map>
#include <tuple>
#include <utility>

#include <App.h>
#include <fmt/format.h>
#include <msgpack.hpp>

#include "drake/common/find_resource.h"
Expand Down Expand Up @@ -48,13 +50,19 @@ class Meshcat::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));
void SetAppPromise(uWS::App* app, uWS::Loop* loop, int port,
us_listen_socket_t* listen_socket) {
app_promise.set_value(std::make_tuple(app, loop, port, listen_socket));
}

// Call this from main thread.
void GetAppFuture() {
std::tie(app_, loop_) = app_future.get();
std::tie(app_, loop_, port_, listen_socket_) = app_future.get();
}

int port() const {
DRAKE_DEMAND(port_ > 0);
return port_;
}

template <typename T>
Expand All @@ -66,8 +74,8 @@ class Meshcat::WebSocketPublisher {
std::stringstream message;

msgpack::zone z;
msgpack::pack(message, std::unordered_map<std::string, msgpack::object>(
{{"type", msgpack::object("set_property", z)},
msgpack::pack(message, std::map<std::string, msgpack::object>(
{{"type", msgpack::object("set_property", z)},
{"path", msgpack::object(path, z)},
{"property", msgpack::object(property, z)},
{"value", msgpack::object(value, z)}}));
Expand All @@ -88,9 +96,20 @@ class Meshcat::WebSocketPublisher {
}
}

void Shutdown() {
// This can be extremely slow. See discussion at
// https://github.com/uNetworking/uWebSockets/discussions/809
us_listen_socket_close(0, listen_socket_);
}

private:
std::promise<std::pair<uWS::App*, uWS::Loop*>> app_promise{};
std::future<std::pair<uWS::App*, uWS::Loop*>> app_future{};
std::promise<std::tuple<uWS::App*, uWS::Loop*, int, us_listen_socket_t*>>
app_promise{};
std::future<std::tuple<uWS::App*, uWS::Loop*, int, us_listen_socket_t*>>
app_future{};

int port_{-1};
us_listen_socket_t* listen_socket_;

// Only loop_->defer() should be called from outside the websocket_thread. See
// the documentation for uWebSockets for further details:
Expand All @@ -99,7 +118,7 @@ class Meshcat::WebSocketPublisher {

// The remaining variables should only be accessed from the websocket_thread.
uWS::App* app_{nullptr};
std::unordered_map<std::string, std::string> set_properties_{};
std::map<std::string, std::string> set_properties_{};
};

Meshcat::Meshcat() {
Expand All @@ -111,7 +130,18 @@ Meshcat::Meshcat() {
publisher_->GetAppFuture();
}

Meshcat::~Meshcat() = default;
Meshcat::~Meshcat() {
publisher_->Shutdown();
JoinWebSocketThread();
}

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(); }

Expand Down Expand Up @@ -152,26 +182,23 @@ void Meshcat::WebsocketMain() {
})
.ws<PerSocketData>("/*", std::move(behavior));

bool listening = false;
us_listen_socket_t* listen_socket = nullptr;
do {
app.listen(
port, LIBUS_LISTEN_EXCLUSIVE_PORT,
[port, &listening](us_listen_socket_t* listenSocket) {
if (listenSocket) {
[port, &listen_socket](us_listen_socket_t* socket) {
if (socket) {
std::cout
<< "Meshcat listening for connections at http://127.0.0.1:"
<< port << std::endl;
listening = true;
listen_socket = socket;
}
});
} while (!listening && port++ <= kMaxPort);
} while (listen_socket == nullptr && port++ <= kMaxPort);

publisher_->SetAppPromise(&app, uWS::Loop::get());
publisher_->SetAppPromise(&app, uWS::Loop::get(), port, listen_socket);

app.run();

// run() should not terminate. If it does, then we've failed.
throw std::runtime_error("Meshcat websocket thread failed");
}

} // namespace geometry
Expand Down
11 changes: 9 additions & 2 deletions geometry/dev/meshcat.h → geometry/meshcat.h
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand All @@ -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. */
Expand Down
4 changes: 2 additions & 2 deletions geometry/dev/meshcat_demo.cc → geometry/meshcat_demo.cc
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
#include "drake/geometry/dev/meshcat.h"
#include "drake/geometry/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
To test, you must manually run `bazel run //geometry: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
Expand Down
80 changes: 80 additions & 0 deletions geometry/test/meshcat_test.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
#include "drake/geometry/meshcat.h"

#include <fmt/format.h>
#include <gmock/gmock.h>
#include <gtest/gtest.h>

namespace drake {
namespace geometry {
namespace {

using ::testing::HasSubstr;

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(system(fmt::format("curl -o /dev/null --silent {}/index.html",
meshcat.web_url())
.c_str()),
0);
EXPECT_EQ(system(fmt::format("curl -o /dev/null --silent {}/main.min.js",
meshcat.web_url())
.c_str()),
0);
EXPECT_EQ(system(fmt::format("curl -o /dev/null --silent {}/favicon.ico",
meshcat.web_url())
.c_str()),
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(
system(fmt::format(
"python3 geometry/test/meshcat_websocket_client.py '{}' {} '{}'",
meshcat.ws_url(), message_num, desired_command_json).c_str()),
0);
}

GTEST_TEST(MeshcatTest, SetProperty) {
drake::geometry::Meshcat meshcat;
meshcat.SetProperty("/Background", "visible", false);
CheckCommand(meshcat, 1, "{"
"\"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, "{"
"\"property\":\"visible\", "
"\"value\":false, "
"\"path\":\"/Background\", "
"\"type\":\"set_property\" "
"}");
CheckCommand(meshcat, 2, "{"
"\"property\":\"visible\", "
"\"value\":false, "
"\"path\":\"/Grid\", "
"\"type\":\"set_property\" "
"}");
}

} // namespace
} // namespace geometry
} // namespace drake
Loading

0 comments on commit e2ad0db

Please sign in to comment.