Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[meshcat] Add realtime rate display to MeshcatVisualizer #16981

Merged
Merged
Show file tree
Hide file tree
Changes from 28 commits
Commits
Show all changes
30 commits
Select commit Hold shift + click to select a range
9358870
Add realtime rate display to MeshcatVisualizer
Apr 18, 2022
8a21e08
Review comments, mostly style
Apr 26, 2022
4423a16
Make rtr plot hidden depending on meshcat params.
Apr 28, 2022
43127c4
Add Timer interface which can be mocked to test realtime rate calcula…
Apr 28, 2022
48ec72c
Add realtimerate display unit tests to Meshcat and realtime rate calc…
Apr 29, 2022
fd52446
Fix time_test whitespace.
Apr 30, 2022
d491ac5
Fix style linting and remove test code from meshcat_visualizer_test.cc
May 4, 2022
9601347
Alphabetize some build parts. Point stats.js repo to head of master b…
May 12, 2022
a43d17f
rename time library "timer" and make SteadyTimer calls not inlined
Jun 28, 2022
20325aa
Naming cleanup and style guide fixes.
Jun 28, 2022
401102b
Make show_stats_plot positive. Change Timer to return doubles and not…
Jun 29, 2022
4d306ce
fix InstantaneousRealtimeRateCalculatorTest to use plain double
Jun 29, 2022
c981b4b
Fix timer.h include path
Jun 29, 2022
69981d1
point new TODOs to #16486
Jun 29, 2022
414b0e1
protect timer copy move assign constructors.
Jun 30, 2022
883e7bf
add pybinding for show_stats_plot and disable the plot in meldis.
Jun 30, 2022
4bf6648
add pybinding for show_stats_plot to pybinding unit tests.
Jun 30, 2022
4aac533
add pybinding Meshcat::SetRealtimeRate.
Jun 30, 2022
90e7098
__repr__ for new MeshcatParams field and fixed pyformatting.
Jul 1, 2022
9e5c255
Merge branch 'master' into feature/rtr_display_merge
pathammer Jul 6, 2022
d376952
platform review comments
Jul 7, 2022
5e84740
small formatting fix and new todo
Jul 7, 2022
72e4db3
make timer_test more robust.
Jul 7, 2022
f9f64e4
comment indentation
Jul 7, 2022
584949a
fix indentation
Jul 7, 2022
56c3b16
rename CalculateRealtimeRate
Jul 7, 2022
48daa57
make timer_test test the function of Start()
Jul 7, 2022
e9c35e8
make steady timer constructor call Start()
Jul 7, 2022
beef7ef
remove unnecessary call to chrono
Jul 7, 2022
2c0e82a
add more strongly worded comment about timer interface ctor
Jul 7, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
9 changes: 7 additions & 2 deletions bindings/pydrake/geometry_py_visualizers.cc
Original file line number Diff line number Diff line change
Expand Up @@ -191,12 +191,15 @@ void DoScalarIndependentDefinitions(py::module m) {
.def_readwrite("port", &MeshcatParams::port, cls_doc.port.doc)
.def_readwrite("web_url_pattern", &MeshcatParams::web_url_pattern,
cls_doc.web_url_pattern.doc)
.def_readwrite("show_stats_plot", &MeshcatParams::show_stats_plot,
cls_doc.show_stats_plot.doc)
.def("__repr__", [](const Class& self) {
return py::str(
"MeshcatParams("
"port={}, "
"web_url_pattern={})")
.format(self.port, self.web_url_pattern);
"web_url_pattern={}, "
"show_stats_plot={})")
.format(self.port, self.web_url_pattern, self.show_stats_plot);
});
}

Expand Down Expand Up @@ -274,6 +277,8 @@ void DoScalarIndependentDefinitions(py::module m) {
const Eigen::Ref<const Eigen::Matrix4d>&>(&Class::SetTransform),
py::arg("path"), py::arg("matrix"), cls_doc.SetTransform.doc_matrix)
.def("Delete", &Class::Delete, py::arg("path") = "", cls_doc.Delete.doc)
.def("SetRealtimeRate", &Class::SetRealtimeRate, py::arg("rate"),
cls_doc.SetRealtimeRate.doc)
.def("SetProperty",
py::overload_cast<std::string_view, std::string, bool>(
&Class::SetProperty),
Expand Down
8 changes: 7 additions & 1 deletion bindings/pydrake/test/geometry_visualizers_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,9 +93,14 @@ def test_meshcat(self):
params = mut.MeshcatParams(
host="*",
port=port,
web_url_pattern="http://host:{port}")
web_url_pattern="http://host:{port}",
show_stats_plot=False)
meshcat = mut.Meshcat(params=params)
self.assertEqual(meshcat.port(), port)
self.assertEqual(repr(params),
("MeshcatParams(port=7051,"
" web_url_pattern=http://host:{port},"
" show_stats_plot=False)"))
with self.assertRaises(RuntimeError):
meshcat2 = mut.Meshcat(port=port)
self.assertIn("http", meshcat.web_url())
Expand Down Expand Up @@ -150,6 +155,7 @@ def test_meshcat(self):
meshcat.DeleteAddedControls()
self.assertIn("data:application/octet-binary;base64",
meshcat.StaticHtml())
meshcat.SetRealtimeRate(1.0)
meshcat.Flush()

# PerspectiveCamera
Expand Down
4 changes: 2 additions & 2 deletions bindings/pydrake/visualization/meldis.py
Original file line number Diff line number Diff line change
Expand Up @@ -237,8 +237,8 @@ def __init__(self, *, meshcat_host=None, meshcat_port=None):
lcm_url = self._lcm.get_lcm_url()
_logger.info(f"Meldis is listening for LCM messages at {lcm_url}")

params = MeshcatParams(host=meshcat_host or 'localhost',
port=meshcat_port)
params = MeshcatParams(host="localhost", port=meshcat_port,
show_stats_plot=False)
self.meshcat = Meshcat(params=params)

viewer = _ViewerApplet(meshcat=self.meshcat)
Expand Down
17 changes: 17 additions & 0 deletions common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ drake_cc_package_library(
":symbolic_latex",
":symbolic_trigonometric_polynomial",
":temp_directory",
":timer",
":type_safe_index",
":unused",
":value",
Expand Down Expand Up @@ -575,6 +576,15 @@ drake_cc_library(
],
)

drake_cc_library(
name = "timer",
srcs = ["timer.cc"],
hdrs = ["timer.h"],
deps = [
":essential",
],
)

drake_cc_library(
name = "value",
srcs = ["value.cc"],
Expand Down Expand Up @@ -1289,6 +1299,13 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "timer_test",
deps = [
":timer",
],
)

drake_cc_googletest(
name = "drake_cc_googletest_main_test_device",
args = ["--magic_number=1.0"],
Expand Down
30 changes: 30 additions & 0 deletions common/test/timer_test.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
#include "drake/common/timer.h"

#include <thread>

#include "gtest/gtest.h"

namespace drake {

GTEST_TEST(TimeTest, Everything) {
SteadyTimer timer;

// Clock starts upon construction. Allow some time to pass and confirm
// positive measurement.
using std::chrono::duration;
const duration<double> kTestInterval = std::chrono::milliseconds(100);
std::this_thread::sleep_for(kTestInterval); // sleep for at least 100ms
const double T1 = timer.Tick();
EXPECT_GT(T1, 0.0);
EXPECT_GE(T1, std::chrono::duration<double>(kTestInterval).count());

// Start restarts the timer, the new measurement should be less than T1.
timer.Start();
const double T2 = timer.Tick();
EXPECT_GT(T2, 0.0);
EXPECT_LT(T2, T1); // ensure we measured less time after call to Start()

// As time progresses, the tick value monotonically increases.
EXPECT_GT(timer.Tick(), T2);
}
} // namespace drake
13 changes: 13 additions & 0 deletions common/timer.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
#include "common/timer.h"

namespace drake {

SteadyTimer::SteadyTimer() { Start(); }

void SteadyTimer::Start() { start_time_ = clock::now(); }

double SteadyTimer::Tick() {
return std::chrono::duration<double>(clock::now() - start_time_).count();
}

} // namespace drake
46 changes: 46 additions & 0 deletions common/timer.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
#pragma once

// TODO(#16486): Remove chrono include by encapsulating into timer.cc
#include <chrono>

#include "drake/common/drake_copyable.h"

/// @file
/// Provides drake::Timer interface and drake::SteadyTimer for timing events.

namespace drake {

/// Abstract base class for timing utility.
class Timer {
public:
/// Timers start upon construction for convenience.
Timer() = default;
virtual ~Timer() = default;

/// Begins timing. Call Start everytime you want to reset the timer to zero.
virtual void Start() = 0;

/// Obtains a timer measurement in seconds.
/// Call this repeatedly to get multiple measurements.
/// @return the amount of time since the timer started.
virtual double Tick() = 0;

protected:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Timer) // protected from slicing
};

/// Implementation of timing utility that uses monotonic
/// std::chrono::steady_clock.
class SteadyTimer final : public Timer {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(SteadyTimer)
SteadyTimer();
void Start() final;
double Tick() final;

private:
using clock = std::chrono::steady_clock;
clock::time_point start_time_;
};

} // namespace drake
19 changes: 19 additions & 0 deletions geometry/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -392,6 +392,22 @@ drake_cc_library(
],
)

genrule(
name = "stats_js_genrule",
srcs = ["@statsjs//:build/stats.min.js"],
outs = ["stats.min.js"],
cmd = "cp $< $@",
visibility = ["//visibility:private"],
)

genrule(
name = "msgpack_lite_js_genrule",
srcs = ["@msgpack_lite_js//:dist/msgpack.min.js"],
outs = ["msgpack.min.js"],
cmd = "cp $< $@",
visibility = ["//visibility:private"],
)

genrule(
name = "meshcat_ico_genrule",
srcs = ["//doc:favicon.ico"],
Expand All @@ -414,6 +430,8 @@ filegroup(
"meshcat.html",
":meshcat.ico",
":meshcat.js",
":msgpack.min.js",
":stats.min.js",
],
visibility = ["//visibility:private"],
)
Expand Down Expand Up @@ -562,6 +580,7 @@ drake_cc_library(
":scene_graph",
"//common:essential",
"//math:geometric_transform",
"//systems/analysis:instantaneous_realtime_rate_calculator",
"//systems/framework:context",
"//systems/framework:diagram_builder",
"//systems/framework:leaf_system",
Expand Down
64 changes: 57 additions & 7 deletions geometry/meshcat.cc
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,10 @@ std::string LoadResource(const std::string& resource_name) {
const std::string& GetUrlContent(std::string_view url_path) {
static const drake::never_destroyed<std::string> meshcat_js(
LoadResource("drake/geometry/meshcat.js"));
static const drake::never_destroyed<std::string> stats_js(
LoadResource("drake/geometry/stats.min.js"));
static const drake::never_destroyed<std::string> msgpack_lite_js(
LoadResource("drake/geometry/msgpack.min.js"));
static const drake::never_destroyed<std::string> meshcat_ico(
LoadResource("drake/geometry/meshcat.ico"));
static const drake::never_destroyed<std::string> meshcat_html(
Expand All @@ -69,6 +73,12 @@ const std::string& GetUrlContent(std::string_view url_path) {
if (url_path == "/meshcat.js") {
return meshcat_js.access();
}
if (url_path == "/stats.min.js") {
return stats_js.access();
}
if (url_path == "/msgpack.min.js") {
return msgpack_lite_js.access();
}
if (url_path == "/favicon.ico") {
return meshcat_ico.access();
}
Expand Down Expand Up @@ -604,6 +614,21 @@ class Meshcat::Impl {
return port_;
}

// This function is public via the PIMPL.
void SetRealtimeRate(double rate) {
DRAKE_DEMAND(IsThread(main_thread_id_));
internal::RealtimeRateData data;
data.rate = rate;
Defer([this, data = std::move(data)]() {
DRAKE_DEMAND(IsThread(websocket_thread_id_));
DRAKE_DEMAND(app_ != nullptr);
std::stringstream message_stream;
msgpack::pack(message_stream, data);
std::string message = message_stream.str();
app_->publish("all", message, uWS::OpCode::BINARY, false);
});
}

// This function is public via the PIMPL.
std::string ws_url() const {
DRAKE_DEMAND(IsThread(main_thread_id_));
Expand Down Expand Up @@ -1363,20 +1388,33 @@ class Meshcat::Impl {
url = url.replace("https://", "wss://")
url = url.replace("/index.html", "/")
url = url.replace("/meshcat.html", "/")
viewer.connect(url);
connection = new WebSocket(url);
connection.binaryType = "arraybuffer";
connection.onmessage = (msg) => handle_message(msg);
connection.onclose = function(evt) {
console.log("onclose:", evt);
}
viewer.connection = connection
} catch (e) {
console.info("Not connected to MeshCat websocket server: ", e);
})""";
size_t pos = html.find(html_connect);
const size_t pos = html.find(html_connect);
DRAKE_DEMAND(pos != std::string::npos);
html.replace(pos, html_connect.size(), std::move(f.get()));

// Insert the javascript directly into the html.
const std::string meshcat_src_link(" src=\"meshcat.js\"");
pos = html.find(meshcat_src_link);
DRAKE_DEMAND(pos != std::string::npos);
html.erase(pos, meshcat_src_link.size());
html.insert(pos+1, GetUrlContent("/meshcat.js"));
std::vector<std::pair<std::string, std::string>> js_paths{
{" src=\"meshcat.js\"", "/meshcat.js"},
{" src=\"stats.min.js\"", "/stats.min.js"},
{" src=\"msgpack.min.js\"", "/msgpack.min.js"},
};

for (const auto& [src_link, url] : js_paths) {
const size_t js_pos = html.find(src_link);
DRAKE_DEMAND(js_pos != std::string::npos);
html.erase(js_pos, src_link.size());
html.insert(js_pos+1, GetUrlContent(url));
}

return html;
}
Expand Down Expand Up @@ -1649,6 +1687,14 @@ class Meshcat::Impl {
ws->send(message_stream.str());
}
}

// Tell client if the realtime rate plot should be hidden
internal::ShowRealtimeRate realtime_rate_message;
realtime_rate_message.show = params_.show_stats_plot;
std::stringstream realtime_message_stream;
msgpack::pack(realtime_message_stream, realtime_rate_message);
ws->send(realtime_message_stream.str());

if (inject_open_fault_.load()) {
throw std::runtime_error(
"InjectWebsocketThreadFault during socket open");
Expand Down Expand Up @@ -1996,6 +2042,10 @@ void Meshcat::Delete(std::string_view path) {
impl().Delete(path);
}

void Meshcat::SetRealtimeRate(double rate) {
impl().SetRealtimeRate(rate);
}

void Meshcat::SetProperty(std::string_view path, std::string property,
bool value) {
impl().SetProperty(path, std::move(property), value);
Expand Down
15 changes: 15 additions & 0 deletions geometry/meshcat.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,11 @@ struct MeshcatParams {
"all interfaces".
*/
std::string web_url_pattern{"http://{host}:{port}"};

/** Determines whether or not to display the stats plot widget in the Meshcat
user interface. This plot including realtime rate and WebGL render
statistics. */
bool show_stats_plot{true};
};

/** Provides an interface to %Meshcat (https://github.com/rdeits/meshcat).
Expand Down Expand Up @@ -353,6 +358,16 @@ class Meshcat {
See @ref meshcat_path for the detailed semantics of deletion. */
void Delete(std::string_view path = "");

// TODO(#16486): add low-pass filter to smooth the Realtime plot
/** Sets the realtime rate that is displayed in the meshcat visualizer stats
strip chart. This rate is the ratio between sim time and real
world time. 1 indicates the simulator is the same speed as real time. 2
indicates running twice as fast as real time, 0.5 is half speed, etc.
@see drake::systems::Simulator::set_target_realtime_rate()
@param rate the realtime rate value to be displayed, will be converted to a
percentage (multiplied by 100) */
void SetRealtimeRate(double rate);

/** Sets a single named property of the object at the given path. For example,
@verbatim
meshcat.SetProperty("/Background", "visible", false);
Expand Down