Skip to content

Commit

Permalink
[geometry] Established 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; avoiding coverage of the throw and join methods is fine).

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 37fd417 commit c7e217a
Show file tree
Hide file tree
Showing 8 changed files with 171 additions and 7 deletions.
18 changes: 18 additions & 0 deletions geometry/dev/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,13 @@
load(
"@drake//tools/skylark:drake_cc.bzl",
"drake_cc_binary",
"drake_cc_googletest",
"drake_cc_library",
)
load(
"@drake//tools/skylark:drake_py.bzl",
"drake_py_binary",
)
load("//tools/lint:lint.bzl", "add_lint_tests")

package(default_visibility = ["//visibility:private"])
Expand Down Expand Up @@ -33,4 +38,17 @@ drake_cc_binary(
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"],
)


add_lint_tests()
30 changes: 23 additions & 7 deletions geometry/dev/meshcat.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
#include <utility>

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

#include "drake/common/find_resource.h"
Expand Down Expand Up @@ -48,13 +49,18 @@ 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) {
app_promise.set_value(std::make_tuple(app, loop, port));
}

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

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

template <typename T>
Expand Down Expand Up @@ -89,8 +95,10 @@ class Meshcat::WebSocketPublisher {
}

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>> app_promise{};
std::future<std::tuple<uWS::App*, uWS::Loop*, int>> app_future{};

int port_{-1};

// Only loop_->defer() should be called from outside the websocket_thread. See
// the documentation for uWebSockets for further details:
Expand All @@ -99,7 +107,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 @@ -113,6 +121,14 @@ Meshcat::Meshcat() {

Meshcat::~Meshcat() = default;

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,
Expand Down Expand Up @@ -166,7 +182,7 @@ void Meshcat::WebsocketMain() {
});
} while (!listening && port++ <= kMaxPort);

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

app.run();

Expand Down
7 changes: 7 additions & 0 deletions geometry/dev/meshcat.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
80 changes: 80 additions & 0 deletions geometry/dev/test/meshcat_test.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
#include "drake/geometry/dev/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/dev/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
40 changes: 40 additions & 0 deletions geometry/dev/test/meshcat_websocket_client.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
# Usage:
# python3 meshcat_websocket_client.py ws_url message_number desired_command_json
#
# This test script connects to a websocket on localhost at `port`, listens for
# `message_number` received messages, unpacks the last message and compares it
# to the dictionary passed via `desired_command_json`.

import asyncio
import json
import sys
import umsgpack
import websockets

async def CheckCommand(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}")
exit(1)

if len(sys.argv) != 4:
print(sys.argv)
print("Usage: python3 meshcat_websocket_client.py ws_url " +
"message_number desired_command_json")
exit(1)

ws_url = sys.argv[1]
message_number = int(sys.argv[2])
desired_command_json = sys.argv[3]
desired_command = json.loads(desired_command_json)

asyncio.get_event_loop().run_until_complete(
CheckCommand(ws_url, message_number, desired_command))

exit(0)
1 change: 1 addition & 0 deletions setup/mac/source_distribution/requirements-test-only.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
jupyter
pandas
six
websockets
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ python3-scipy-dbg
python3-six
python3-tk-dbg
python3-uritemplate
python3-websockets
python3-yaml-dbg
python3-zmq-dbg
valgrind
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ python3-scipy-dbg
python3-six
python3-tk-dbg
python3-uritemplate
python3-websockets
python3-yaml-dbg
python3-zmq-dbg
valgrind
Expand Down

0 comments on commit c7e217a

Please sign in to comment.