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 RobotLocomotion#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 f3067b1 commit 7a9a095
Show file tree
Hide file tree
Showing 12 changed files with 313 additions and 106 deletions.
45 changes: 45 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,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(
Expand Down
36 changes: 0 additions & 36 deletions geometry/dev/BUILD.bazel

This file was deleted.

32 changes: 0 additions & 32 deletions geometry/dev/meshcat_demo.cc

This file was deleted.

115 changes: 80 additions & 35 deletions geometry/dev/meshcat.cc → geometry/meshcat.cc
Original file line number Diff line number Diff line change
@@ -1,26 +1,28 @@
#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"
#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::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 file: " + filename);
throw std::runtime_error("Error opening resource: " + resource_name);
std::stringstream content;
content << file.rdbuf();
file.close();
Expand All @@ -45,29 +47,45 @@ class Meshcat::WebSocketPublisher {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(WebSocketPublisher);

WebSocketPublisher() : app_future(app_promise.get_future()) {}
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) {
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) {
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() {
std::tie(app_, loop_) = app_future.get();
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 <typename T>
void SetProperty(const std::string& path, const std::string& property,
void SetProperty(std::string_view path, std::string_view property,
const T& value) {
DRAKE_ASSERT(app_ != nullptr);
DRAKE_ASSERT(loop_ != nullptr);
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::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 @@ -76,30 +94,47 @@ class Meshcat::WebSocketPublisher {
// scope.
loop_->defer([this, path, property, msg = message.str()]() {
app_->publish("all", msg, uWS::OpCode::BINARY, false);
set_properties_[path + "/" + property] = msg;
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<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_{};

// These variables should only be accessed in the main thread.
std::thread::id main_thread_id_{};
std::future<std::tuple<uWS::App*, uWS::Loop*, int, us_listen_socket_t*>>
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<std::string, std::string> 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};

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

Meshcat::Meshcat() {
Expand All @@ -111,23 +146,36 @@ Meshcat::Meshcat() {
publisher_->GetAppFuture();
}

Meshcat::~Meshcat() = default;
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(const std::string& path, const std::string& property,
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());

// Preload the three files we will serve (always).
static const drake::never_destroyed<std::string> index_html(
LoadFile("drake/external/meshcat/dist/index.html"));
LoadResource("drake/external/meshcat/dist/index.html"));
static const drake::never_destroyed<std::string> main_min_js(
LoadFile("drake/external/meshcat/dist/main.min.js"));
LoadResource("drake/external/meshcat/dist/main.min.js"));
static const drake::never_destroyed<std::string> favicon_ico(
LoadFile("drake/doc/favicon.ico"));
LoadResource("drake/doc/favicon.ico"));
int port = 7001;
const int kMaxPort = 7099;

Expand All @@ -152,26 +200,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
13 changes: 10 additions & 3 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 All @@ -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:
Expand Down
Loading

0 comments on commit 7a9a095

Please sign in to comment.