forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
meshcat.cc
2524 lines (2241 loc) · 93.2 KB
/
meshcat.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#include "drake/geometry/meshcat.h"
#include <algorithm>
#include <atomic>
#include <cctype>
#include <exception>
#include <fstream>
#include <functional>
#include <future>
#include <map>
#include <optional>
#include <regex>
#include <set>
#include <sstream>
#include <string>
#include <thread>
#include <tuple>
#include <utility>
#include <App.h>
#include <common_robotics_utilities/base64_helpers.hpp>
#include <fmt/format.h>
#include <msgpack.hpp>
#include <uuid.h>
#include "drake/common/drake_export.h"
#include "drake/common/drake_throw.h"
#include "drake/common/find_resource.h"
#include "drake/common/network_policy.h"
#include "drake/common/never_destroyed.h"
#include "drake/common/scope_exit.h"
#include "drake/common/ssize.h"
#include "drake/common/text_logging.h"
#include "drake/geometry/meshcat_types.h"
#ifdef BOOST_VERSION
# error Drake should be using the non-boost flavor of msgpack.
#endif
// Steal one function declaration from usockets/src/internal/internal.h.
extern "C" {
void us_internal_free_closed_sockets(struct us_loop_t*);
}
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<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> meshcat_ico(
LoadResource("drake/geometry/meshcat.ico"));
static const drake::never_destroyed<std::string> meshcat_html(
LoadResource("drake/geometry/meshcat.html"));
static const drake::never_destroyed<std::string> empty;
if ((url_path == "/")
|| (url_path == "/index.html")
|| (url_path == "/meshcat.html")) {
return meshcat_html.access();
}
if (url_path == "/meshcat.js") {
return meshcat_js.access();
}
if (url_path == "/stats.min.js") {
return stats_js.access();
}
if (url_path == "/favicon.ico") {
return meshcat_ico.access();
}
drake::log()->warn("Ignoring Meshcat http request for {}", url_path);
return empty.access();
}
template <typename Mapping>
[[noreturn]] void ThrowThingNotFound(
std::string_view thing, std::string_view name, Mapping thing_map) {
std::vector<std::string> keys;
for (const auto& map_pair : thing_map) {
keys.push_back(map_pair.first);
}
throw std::logic_error(
fmt::format("Meshcat does not have any {} named {}. The "
"registered {} names are ({}).",
thing, name, thing, fmt::join(keys, ", ")));
}
} // namespace
namespace drake {
namespace geometry {
namespace {
using math::RigidTransformd;
using math::RotationMatrixd;
constexpr static bool kSsl = false;
constexpr static bool kIsServer = true;
struct PerSocketData {
// Intentionally left empty.
};
using WebSocket = uWS::WebSocket<kSsl, kIsServer, PerSocketData>;
using MsgPackMap = std::map<std::string, msgpack::object>;
// Encode the meshcat command into a Javascript fetch() command. The particular
// syntax using `fetch()` was replicated from the corresponding functionality in
// meshcat-python.
std::string CreateCommand(const std::string& data) {
return fmt::format(R"""(
fetch("data:application/octet-binary;base64,{}")
.then(res => res.arrayBuffer())
.then(buffer => viewer.handle_command_bytearray(new Uint8Array(buffer)));
)""",
common_robotics_utilities::base64_helpers::Encode(
std::vector<uint8_t>(data.begin(), data.end())));
}
class SceneTreeElement {
public:
// Member access methods (object_, transform_, and properties_ should be
// effectively public).
const std::optional<std::string>& object() const { return object_; }
std::optional<std::string>& object() { return object_; }
const std::optional<std::string>& transform() const { return transform_; }
std::optional<std::string>& transform() { return transform_; }
const std::map<std::string, std::string>& properties() const {
return properties_;
}
std::map<std::string, std::string>& properties() { return properties_; }
// Returns this element or a descendant, based on a recursive evaluation of
// the `path`. Adds new elements if they do not exist. Comparable to
// std::map::operator[].
SceneTreeElement& operator[](std::string_view path) {
while (!path.empty() && path.front() == '/') {
path.remove_prefix(1);
}
if (path.empty()) {
return *this;
}
auto loc = path.find_first_of("/");
std::string name(path.substr(0, loc));
auto child = children_.find(name);
// Create the child if it doesn't exist.
if (child == children_.end()) {
child =
children_.emplace(name, std::make_unique<SceneTreeElement>()).first;
}
if (loc == std::string_view::npos) {
return *child->second;
} else {
return (*child->second)[path.substr(loc + 1)];
}
}
// Returns a pointer to `this` element or a descendant, based on a recursive
// evaluation of the `path`, or nullptr if `path` does not exist.
const SceneTreeElement* Find(std::string_view path) const {
while (!path.empty() && path.front() == '/') {
path.remove_prefix(1);
}
if (path.empty()) {
return this;
}
auto loc = path.find_first_of("/");
std::string name(path.substr(0, loc));
auto child = children_.find(name);
if (child == children_.end()) {
return nullptr;
}
if (loc == std::string_view::npos) {
return child->second.get();
} else {
return child->second->Find(path.substr(loc + 1));
}
}
// Deletes `path` from the tree. See Meshcat::Delete.
void Delete(std::string_view path) {
while (!path.empty() && path.front() == '/') {
path.remove_prefix(1);
}
if (path.empty()) {
// To match javascript, we don't delete the empty path.
return;
}
auto loc = path.find_first_of("/");
auto child = children_.find(std::string(path.substr(0, loc)));
if (child == children_.end()) {
return;
}
if (loc == std::string_view::npos) {
children_.erase(child);
return;
}
child->second->Delete(path.substr(loc + 1));
}
// Sends the entire tree on `ws`.
void Send(WebSocket* ws) {
if (object_) {
ws->send(*object_);
}
if (transform_) {
ws->send(*transform_);
}
for (const auto& [_, msg] : properties_) {
ws->send(msg);
}
for (const auto& [_, child] : children_) {
child->Send(ws);
}
}
// Returns a string which implements the entire tree directly in javascript.
// This is intended for use in generating a "static html" of the scene.
std::string CreateCommands() {
std::string html;
if (object_) {
html += CreateCommand(*object_);
}
if (transform_) {
html += CreateCommand(*transform_);
}
for (const auto& [_, msg] : properties_) {
html += CreateCommand(msg);
}
for (const auto& [_, child] : children_) {
html += child->CreateCommands();
}
return html;
}
private:
// Note: We use std::optional here to clearly denote the variables that have
// not been set, and therefore need not be sent over the websocket.
// The msgpack'd set_object command.
std::optional<std::string> object_{std::nullopt};
// The msgpack'd set_transform command.
std::optional<std::string> transform_{std::nullopt};
// The msgpack'd set_property command(s).
std::map<std::string, std::string> properties_{};
// Children, with the key value denoting their (relative) path name.
std::map<std::string, std::unique_ptr<SceneTreeElement>> children_{};
};
class MeshcatShapeReifier : public ShapeReifier {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(MeshcatShapeReifier);
explicit MeshcatShapeReifier(uuids::uuid_random_generator* uuid_generator)
: uuid_generator_(uuid_generator) {
DRAKE_DEMAND(uuid_generator != nullptr);
}
~MeshcatShapeReifier() = default;
using ShapeReifier::ImplementGeometry;
// @tparam MeshType is either Mesh or Convex.
template <typename MeshType>
void ImplementMesh(const MeshType& mesh, void* data) {
DRAKE_DEMAND(data != nullptr);
auto& lumped = *static_cast<internal::LumpedObjectData*>(data);
// TODO(russt): Use file contents to generate the uuid, and avoid resending
// meshes unless necessary. Using the filename is tempting, but that leads
// to problems when the file contents change on disk.
std::string format = mesh.extension();
format.erase(0, 1); // remove the . from the extension
std::ifstream input(mesh.filename(), std::ios::binary | std::ios::ate);
if (!input.is_open()) {
drake::log()->warn("Meshcat: Could not open mesh filename {}",
mesh.filename());
return;
}
// We simply dump the binary contents of the file into the data field of the
// message. The javascript meshcat takes care of the rest.
const int obj_size = input.tellg();
input.seekg(0, std::ios::beg);
std::string mesh_data;
mesh_data.reserve(obj_size);
mesh_data.assign(std::istreambuf_iterator<char>(input),
std::istreambuf_iterator<char>());
// TODO(russt): MeshCat.jl/src/mesh_files.jl loads dae with textures, also.
// TODO(russt): Make this mtllib parsing more robust (right now commented
// mtllib lines will match, too, etc).
size_t mtllib_pos;
if (format == "obj" &&
(mtllib_pos = mesh_data.find("mtllib ")) != std::string::npos) {
mtllib_pos += 7; // Advance to after the actual "mtllib " string.
std::string mtllib_string =
mesh_data.substr(mtllib_pos, mesh_data.find('\n', mtllib_pos));
std::smatch matches;
std::regex_search(mtllib_string, matches, std::regex("\\s*([^\\s]+)"));
// Note: We do a minimal parsing manually here. tinyobj does too much
// work (actually loading all of the content) and also does not give
// access to the intermediate data that we need to pass to meshcat, like
// the resource names in the mtl file. This is also the approach taken
// in MeshCat.jl/src/mesh_files.jl.
auto& meshfile_object =
lumped.object.emplace<internal::MeshFileObjectData>();
meshfile_object.uuid = uuids::to_string((*uuid_generator_)());
meshfile_object.format = std::move(format);
meshfile_object.data = std::move(mesh_data);
std::string mtllib = matches.str(1);
// Use filename path as the base directory for textures.
const std::filesystem::path basedir =
std::filesystem::path(mesh.filename()).parent_path();
// Read .mtl file into geometry.mtl_library.
std::ifstream mtl_stream(basedir / mtllib, std::ios::ate);
if (mtl_stream.is_open()) {
int mtl_size = mtl_stream.tellg();
mtl_stream.seekg(0, std::ios::beg);
meshfile_object.mtl_library.reserve(mtl_size);
meshfile_object.mtl_library.assign(
std::istreambuf_iterator<char>(mtl_stream),
std::istreambuf_iterator<char>());
// Scan .mtl file for map_ lines. For each, load the file and add
// the contents to geometry.resources.
// The syntax (http://paulbourke.net/dataformats/mtl/) is e.g.
// map_Ka -options args filename
// Here we ignore the options and only extract the filename (by
// extracting the last word before the end of line/string).
// - "map_.+" matches the map_ plus any options,
// - "\s" matches one whitespace (before the filename),
// - "[^\s]+" matches the filename, and
// - "[$\r\n]" matches the end of string or end of line.
// TODO(russt): This parsing could still be more robust.
std::regex map_regex(R"""(map_.+\s([^\s]+)\s*[$\r\n])""");
for (std::sregex_iterator iter(meshfile_object.mtl_library.begin(),
meshfile_object.mtl_library.end(),
map_regex);
iter != std::sregex_iterator(); ++iter) {
std::string map = iter->str(1);
std::ifstream map_stream(basedir / map,
std::ios::binary | std::ios::ate);
if (map_stream.is_open()) {
int map_size = map_stream.tellg();
map_stream.seekg(0, std::ios::beg);
std::vector<uint8_t> map_data;
map_data.reserve(map_size);
map_data.assign(std::istreambuf_iterator<char>(map_stream),
std::istreambuf_iterator<char>());
meshfile_object.resources.try_emplace(
map, std::string("data:image/png;base64,") +
common_robotics_utilities::base64_helpers::Encode(
map_data));
} else {
drake::log()->warn(
"Meshcat: Failed to load texture. \"{}\" references {}, but "
"Meshcat could not open filename \"{}\"",
(basedir / mtllib).string(), map, (basedir / map).string());
}
}
} else {
drake::log()->warn(
"Meshcat: Failed to load texture. {} references {}, but Meshcat "
"could not open filename \"{}\"",
mesh.filename(), mtllib, (basedir / mtllib).string());
}
Eigen::Map<Eigen::Matrix4d> matrix(meshfile_object.matrix);
matrix(0, 0) = mesh.scale();
matrix(1, 1) = mesh.scale();
matrix(2, 2) = mesh.scale();
} else if (format == "gltf") {
auto& meshfile_object =
lumped.object.emplace<internal::MeshFileObjectData>();
meshfile_object.uuid = uuids::to_string((*uuid_generator_)());
meshfile_object.format = std::move(format);
meshfile_object.data = std::move(mesh_data);
Eigen::Map<Eigen::Matrix4d> matrix(meshfile_object.matrix);
matrix(0, 0) = mesh.scale();
matrix(1, 1) = mesh.scale();
matrix(2, 2) = mesh.scale();
} else {
// We have a mesh that isn't a .gltf nor an obj with mtl. So, we'll make
// mesh file *geometry* instead of mesh file *object*. This will most
// typically be a Collada .dae file, an .stl, or simply an .obj that
// doesn't reference an .mtl.
// TODO(SeanCurtis-TRI): This doesn't work for STL even though meshcat
// supports STL. Meshcat treats STL differently from obj or dae.
// https://github.com/meshcat-dev/meshcat/blob/4b4f8ffbaa5f609352ea6227bd5ae8207b579c70/src/index.js#L130-L146.
// The "data" property of the _meshfile_geometry for obj and dae are
// simply passed along verbatim. But for STL it is interpreted as a
// buffer. However, we're not passing the data in a way that deserializes
// into a data array. So, either meshcat needs to change how it gets
// STL (being more permissive), or we need to change how we transmit STL
// data.
// TODO(SeanCurtis-TRI): Provide test showing that .dae works.
if (format != "obj" && format != "dae") {
// Note: We send the data along to meshcat regardless relying on meshcat
// to ignore the mesh and move on. The *path* will still exist.
static const logging::Warn one_time(
"Drake's Meshcat only supports Mesh/Convex specifications which "
"use .obj, .gltf, or .dae files. Mesh specifications using other "
"mesh types (e.g., .stl, etc.) will not be visualized.");
}
auto geometry = std::make_unique<internal::MeshFileGeometryData>();
geometry->uuid = uuids::to_string((*uuid_generator_)());
geometry->format = std::move(format);
geometry->data = std::move(mesh_data);
lumped.geometry = std::move(geometry);
auto& meshcat_mesh = lumped.object.emplace<internal::MeshData>();
Eigen::Map<Eigen::Matrix4d> matrix(meshcat_mesh.matrix);
matrix(0, 0) = mesh.scale();
matrix(1, 1) = mesh.scale();
matrix(2, 2) = mesh.scale();
}
}
void ImplementGeometry(const Box& box, void* data) override {
DRAKE_DEMAND(data != nullptr);
auto& lumped = *static_cast<internal::LumpedObjectData*>(data);
lumped.object = internal::MeshData();
auto geometry = std::make_unique<internal::BoxGeometryData>();
geometry->uuid = uuids::to_string((*uuid_generator_)());
geometry->width = box.width();
// Three.js uses height for the y axis; Drake uses depth.
geometry->height = box.depth();
geometry->depth = box.height();
lumped.geometry = std::move(geometry);
}
void ImplementGeometry(const Capsule& capsule, void* data) override {
DRAKE_DEMAND(data != nullptr);
auto& lumped = *static_cast<internal::LumpedObjectData*>(data);
auto& mesh = lumped.object.emplace<internal::MeshData>();
auto geometry = std::make_unique<internal::CapsuleGeometryData>();
geometry->uuid = uuids::to_string((*uuid_generator_)());
geometry->radius = capsule.radius();
geometry->length = capsule.length();
lumped.geometry = std::move(geometry);
// Meshcat cylinders have their long axis in y.
Eigen::Map<Eigen::Matrix4d>(mesh.matrix) =
RigidTransformd(RotationMatrixd::MakeXRotation(M_PI / 2.0))
.GetAsMatrix4();
}
void ImplementGeometry(const Convex& mesh, void* data) override {
ImplementMesh(mesh, data);
}
void ImplementGeometry(const Cylinder& cylinder, void* data) override {
DRAKE_DEMAND(data != nullptr);
auto& lumped = *static_cast<internal::LumpedObjectData*>(data);
auto& mesh = lumped.object.emplace<internal::MeshData>();
auto geometry = std::make_unique<internal::CylinderGeometryData>();
geometry->uuid = uuids::to_string((*uuid_generator_)());
geometry->radiusBottom = cylinder.radius();
geometry->radiusTop = cylinder.radius();
geometry->height = cylinder.length();
lumped.geometry = std::move(geometry);
// Meshcat cylinders have their long axis in y.
Eigen::Map<Eigen::Matrix4d>(mesh.matrix) =
RigidTransformd(RotationMatrixd::MakeXRotation(M_PI / 2.0))
.GetAsMatrix4();
}
void ImplementGeometry(const Ellipsoid& ellipsoid, void* data) override {
// Implemented as a Sphere stretched by a diagonal transform.
DRAKE_DEMAND(data != nullptr);
auto& lumped = *static_cast<internal::LumpedObjectData*>(data);
auto& mesh = lumped.object.emplace<internal::MeshData>();
auto geometry = std::make_unique<internal::SphereGeometryData>();
geometry->uuid = uuids::to_string((*uuid_generator_)());
geometry->radius = 1;
lumped.geometry = std::move(geometry);
Eigen::Map<Eigen::Matrix4d> matrix(mesh.matrix);
matrix(0, 0) = ellipsoid.a();
matrix(1, 1) = ellipsoid.b();
matrix(2, 2) = ellipsoid.c();
}
void ImplementGeometry(const HalfSpace&, void*) override {
// TODO(russt): Use PlaneGeometry with fields width, height,
// widthSegments, heightSegments
drake::log()->warn("Meshcat does not display HalfSpace geometry (yet).");
}
void ImplementGeometry(const Mesh& mesh, void* data) override {
ImplementMesh(mesh, data);
}
void ImplementGeometry(const MeshcatCone& cone, void* data) override {
DRAKE_DEMAND(data != nullptr);
auto& lumped = *static_cast<internal::LumpedObjectData*>(data);
auto& mesh = lumped.object.emplace<internal::MeshData>();
auto geometry = std::make_unique<internal::CylinderGeometryData>();
geometry->uuid = uuids::to_string((*uuid_generator_)());
geometry->radiusBottom = 0;
geometry->radiusTop = 1.0;
geometry->height = cone.height();
lumped.geometry = std::move(geometry);
// Meshcat cylinders have their long axis in y and are centered at the
// origin. A cone is just a cylinder with radiusBottom=0. So we transform
// here, in addition to scaling to support non-uniform principle axes.
Eigen::Map<Eigen::Matrix4d>(mesh.matrix) =
Eigen::Vector4d{cone.a(), cone.b(), 1.0, 1.0}.asDiagonal() *
RigidTransformd(RotationMatrixd::MakeXRotation(M_PI / 2.0),
Eigen::Vector3d{0, 0, cone.height() / 2.0})
.GetAsMatrix4();
}
void ImplementGeometry(const Sphere& sphere, void* data) override {
DRAKE_DEMAND(data != nullptr);
auto& lumped = *static_cast<internal::LumpedObjectData*>(data);
lumped.object = internal::MeshData();
auto geometry = std::make_unique<internal::SphereGeometryData>();
geometry->uuid = uuids::to_string((*uuid_generator_)());
geometry->radius = sphere.radius();
lumped.geometry = std::move(geometry);
}
private:
uuids::uuid_random_generator* const uuid_generator_{};
};
int ToMeshcatColor(const Rgba& rgba) {
// Note: The returned color discards the alpha value, which is handled
// separately (e.g. by the opacity field in the material properties).
return (static_cast<int>(255 * rgba.r()) << 16) +
(static_cast<int>(255 * rgba.g()) << 8) +
static_cast<int>(255 * rgba.b());
}
// Meshcat inherits three.js's y-up world and it is applied to camera and
// camera target positions. To simply set the object's position property, we
// need to express the position in three.js's y-up world frame.
// It's simply a 90-degree rotation around the x-axis, so we hard-code it here.
Eigen::Vector3d MeshcatYUpPosition(const Eigen::Vector3d& p_WP) {
return Eigen::Vector3d(p_WP.x(), p_WP.z(), -p_WP.y());
}
} // namespace
class Meshcat::Impl {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(Impl);
// Some implementation notes for this Impl constructor:
//
// It must not call any nontrivial class methods. In general self-calls from
// a constructor should always be treated with caution, but it's especially
// important in this case because of the complicated threading and state
// invariants that we need to maintain.
//
// It launches the websocket thread and waits for the thread to reply that
// either the application started listening successfully, or else failed.
//
// If the websocket thread failed to bind to a port, then this constructor
// will first join the websocket thread and then throw an exception; the
// destructor will not be run.
//
// Otherwise, upon success the postconditions are that both:
// loop_ is non-null; and
// mode_ is either kFinished (the typical case) or possibly kStopping (in
// the unusual case where websocket thread faulted soon after starting).
explicit Impl(const MeshcatParams& params)
: prefix_("/drake"),
main_thread_id_(std::this_thread::get_id()),
params_(params) {
DRAKE_THROW_UNLESS(!params.port.has_value() || *params.port == 0 ||
*params.port >= 1024);
if (!drake::internal::IsNetworkingAllowed("meshcat")) {
throw std::runtime_error(
"Meshcat has been disabled via the DRAKE_ALLOW_NETWORK environment "
"variable");
}
// Sanity-check the pattern, by passing it (along with dummy host and port
// values) through to fmt to allow any fmt-specific exception to percolate.
// Then, confirm that the user's pattern started with a valid protocol.
const std::string url = fmt::format(
fmt_runtime(params.web_url_pattern),
fmt::arg("host", "foo"), fmt::arg("port", 1));
if (url.substr(0, 4) != "http") {
throw std::logic_error("The web_url_pattern must be http:// or https://");
}
// Fetch the index once to be sure that we preload the content.
GetUrlContent("/");
std::promise<std::tuple<int, bool>> app_promise;
std::future<std::tuple<int, bool>> app_future =
app_promise.get_future();
websocket_thread_ = std::thread(
&Impl::WrappedWebSocketMain, this, std::move(app_promise),
params.host, params.port);
bool connected;
std::tie(port_, connected) = app_future.get();
if (!connected) {
mode_.store(kFinished);
websocket_thread_.join();
throw std::runtime_error("Meshcat failed to open a websocket port.");
}
}
~Impl() {
DRAKE_DEMAND(IsThread(main_thread_id_));
// Ensure that the App::run loop stops, in case it hasn't already done so.
Defer([this]() {
DRAKE_DEMAND(IsThread(websocket_thread_id_));
Shutdown();
});
// Tell the websocket thread that we'll never call Defer() again,
// and then wait for it to exit.
mode_.store(kFinished);
websocket_thread_.join();
}
// Throws an exception if the websocket thread has died.
// This function is a file-internal helper, not public in the PIMPL.
//
// This should called from every public function of the outer class (other
// than the destructor) before doing any other real work, so that we can pass
// along error conditions from the websocket thread back onto the main thread.
//
// Don't fall into a TOCTOU trap here -- just because this function returned
// successfully does *not* mean that the websocket thread is still running; it
// might have crashed immediately after this check. Calling code should not
// presume that success here means that additional calls into the websocket
// will continue to succeed.
void ThrowIfWebsocketThreadExited() const {
DRAKE_DEMAND(IsThread(main_thread_id_));
// N.B. Refer to the comments on the `mode_` and `loop_` class member
// fields to help understand what's happening here.
if (mode_.load() != kNominal) {
mode_.store(kFinished);
throw std::runtime_error(
"Meshcat's internal websocket thread exited unexpectedly");
}
}
// This function is public via the PIMPL.
std::string web_url() const {
DRAKE_DEMAND(IsThread(main_thread_id_));
const std::string& host = params_.host;
const bool is_localhost = host.empty() || host == "*";
const std::string display_host = is_localhost ? "localhost" : host;
return fmt::format(
fmt_runtime(params_.web_url_pattern),
fmt::arg("host", display_host),
fmt::arg("port", port_));
}
// This function is public via the PIMPL.
int port() const {
DRAKE_DEMAND(IsThread(main_thread_id_));
return port_;
}
// This function is public via the PIMPL.
void SetRealtimeRate(double rate) {
DRAKE_DEMAND(IsThread(main_thread_id_));
realtime_rate_ = rate;
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.
double GetRealtimeRate() const {
DRAKE_DEMAND(IsThread(main_thread_id_));
return realtime_rate_;
}
// This function is public via the PIMPL.
std::string ws_url() const {
DRAKE_DEMAND(IsThread(main_thread_id_));
const std::string http_url = web_url();
DRAKE_DEMAND(http_url.substr(0, 4) == "http");
return "ws" + http_url.substr(4);
}
// This function is public via the PIMPL.
int GetNumActiveConnections() const {
DRAKE_DEMAND(IsThread(main_thread_id_));
return num_websockets_.load();
}
// This function is public via the PIMPL.
void Flush() const {
DRAKE_DEMAND(IsThread(main_thread_id_));
// We simply loop until the backpressure is zero. In each iteration, if
// the connections have any backpressure, then we sleep the main thread to
// let the websocket thread drain.
//
// Note: The following attempts to avoid the explicit sleep failed:
// - loop_->defer(callback) does not drain automatically between executing
// the deferred callbacks.
// - calling app_->topicTree->drain() or ws->send("") did not actually
// force any drainage.
//
// It *is* possible to monitor the drainage by registering the
// behavior.drain callback on the websocket connection, but we avoid
// explicitly locking the main thread to wait for the drainage in order to
// keep the thread logic simpler.
int main_backpressure;
// Set a very conservative iteration limit; since we sleep for .1 seconds
// on each iteration, this corresponds to (approximately) 10 minutes.
const int kIterationLimit{6000};
int iteration = 0;
do {
std::promise<int> p;
std::future<int> f = p.get_future();
Defer([this, p = std::move(p)]() mutable {
DRAKE_DEMAND(IsThread(websocket_thread_id_));
int websocket_backpressure = 0;
for (WebSocket* ws : websockets_) {
websocket_backpressure += ws->getBufferedAmount();
}
p.set_value(websocket_backpressure);
});
main_backpressure = f.get();
if (main_backpressure > 0) {
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}
++iteration;
} while (main_backpressure > 0 && iteration < kIterationLimit);
if (main_backpressure > 0) {
drake::log()->warn(
"Meshcat::Flush() reached an iteration limit before the buffer could "
"be completely flushed.");
}
}
// This function is public via the PIMPL.
void SetObject(std::string_view path, const Shape& shape, const Rgba& rgba) {
DRAKE_DEMAND(IsThread(main_thread_id_));
uuids::uuid_random_generator uuid_generator{generator_};
internal::SetObjectData data;
data.path = FullPath(path);
// TODO(russt): This current meshcat set_object interface couples geometry,
// material, and object for convenience, but we might consider decoupling
// them again for efficiency. We don't want to send meshes over the network
// (which could be from the cloud to a local browser) more than necessary.
MeshcatShapeReifier reifier(&uuid_generator);
shape.Reify(&reifier, &data.object);
if (std::holds_alternative<std::monostate>(data.object.object)) {
// Then this shape is not supported, and I should not send the message,
// nor add the object to the tree.
return;
}
if (std::holds_alternative<internal::MeshData>(data.object.object)) {
auto& meshfile_object = std::get<internal::MeshData>(data.object.object);
DRAKE_DEMAND(data.object.geometry != nullptr);
meshfile_object.geometry = data.object.geometry->uuid;
auto material = std::make_unique<internal::MaterialData>();
material->uuid = uuids::to_string(uuid_generator());
material->type = "MeshPhongMaterial";
material->color = ToMeshcatColor(rgba);
// TODO(russt): Most values are taken verbatim from meshcat-python.
material->reflectivity = 0.5;
material->side = SideOfFaceToRender::kDoubleSide;
// From meshcat-python: Three.js allows a material to have an opacity
// which is != 1, but to still be non - transparent, in which case the
// opacity only serves to desaturate the material's color. That's a
// pretty odd combination of things to want, so by default we just use
// the opacity value to decide whether to set transparent to True or
// False.
material->transparent = (rgba.a() != 1.0);
material->opacity = rgba.a();
material->linewidth = 1.0;
material->wireframe = false;
material->wireframeLineWidth = 1.0;
meshfile_object.uuid = uuids::to_string(uuid_generator());
meshfile_object.material = material->uuid;
data.object.material = std::move(material);
}
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);
// TODO(russt): Consider using msgpack::sbuffer instead of stringstream
// (here and throughout) to avoid this copy.
// https://github.com/redboltz/msgpack-c/wiki/v2_0_cpp_packer
std::string message = message_stream.str();
app_->publish("all", message, uWS::OpCode::BINARY, false);
SceneTreeElement& e = scene_tree_root_[data.path];
e.object() = std::move(message);
});
}
// This function is public via the PIMPL.
void SetObject(std::string_view path, const perception::PointCloud& cloud,
double point_size, const Rgba& rgba) {
DRAKE_DEMAND(IsThread(main_thread_id_));
uuids::uuid_random_generator uuid_generator{generator_};
internal::SetObjectData data;
data.path = FullPath(path);
auto geometry = std::make_unique<internal::BufferGeometryData>();
geometry->uuid = uuids::to_string(uuid_generator());
geometry->position = cloud.xyzs();
if (cloud.has_rgbs()) {
geometry->color = cloud.rgbs().cast<float>()/255.0;
}
data.object.geometry = std::move(geometry);
auto material = std::make_unique<internal::MaterialData>();
material->uuid = uuids::to_string(uuid_generator());
material->type = "PointsMaterial";
material->color = ToMeshcatColor(rgba);
material->transparent = (rgba.a() != 1.0);
material->opacity = rgba.a();
material->size = point_size;
material->vertexColors = cloud.has_rgbs();
data.object.material = std::move(material);
internal::MeshData mesh;
mesh.uuid = uuids::to_string(uuid_generator());
mesh.type = "Points";
mesh.geometry = data.object.geometry->uuid;
mesh.material = data.object.material->uuid;
data.object.object = std::move(mesh);
Defer([this, data = std::move(data)]() {
std::stringstream message_stream;
msgpack::pack(message_stream, data);
std::string message = message_stream.str();
app_->publish("all", message, uWS::OpCode::BINARY, false);
SceneTreeElement& e = scene_tree_root_[data.path];
e.object() = std::move(message);
});
}
// This function is public via the PIMPL.
void SetObject(std::string_view path, const TriangleSurfaceMesh<double>& mesh,
const Rgba& rgba, bool wireframe,
double wireframe_line_width, SideOfFaceToRender side) {
DRAKE_DEMAND(IsThread(main_thread_id_));
Eigen::Matrix3Xd vertices(3, mesh.num_vertices());
for (int i = 0; i < mesh.num_vertices(); ++i) {
vertices.col(i) = mesh.vertex(i);
}
Eigen::Matrix3Xi faces(3, mesh.num_triangles());
for (int i = 0; i < mesh.num_triangles(); ++i) {
const auto& e = mesh.element(i);
for (int j = 0; j < 3; ++j) {
faces(j, i) = e.vertex(j);
}
}
SetTriangleMesh(path, vertices, faces, rgba, wireframe,
wireframe_line_width, side);
}
// This function is public via the PIMPL.
void SetLine(std::string_view path,
const Eigen::Ref<const Eigen::Matrix3Xd>& vertices,
double line_width, const Rgba& rgba) {
DRAKE_DEMAND(IsThread(main_thread_id_));
const bool kLineSegments = false;
SetLineImpl(path, vertices, line_width, rgba, kLineSegments);
}
// This function is public via the PIMPL.
void SetLineSegments(std::string_view path,
const Eigen::Ref<const Eigen::Matrix3Xd>& start,
const Eigen::Ref<const Eigen::Matrix3Xd>& end,
double line_width, const Rgba& rgba) {
DRAKE_DEMAND(IsThread(main_thread_id_));
DRAKE_THROW_UNLESS(start.cols() == end.cols());
// The LineSegments loader in three.js take the same data structure as Line,
// but takes every consecutive pair of vertices as a (start, end).
Eigen::Matrix<double, 6, Eigen::Dynamic> vstack(6, start.cols());
vstack << start, end;
Eigen::Map<Eigen::Matrix3Xd> vertices(vstack.data(), 3, 2*start.cols());
const bool kLineSegments = true;
SetLineImpl(path, vertices, line_width, rgba, kLineSegments);
}
// This function is internal to the PIMPL, used to implement the prior two
// functions (SetLine and SetLineSegments).
void SetLineImpl(std::string_view path,
const Eigen::Ref<const Eigen::Matrix3Xd>& vertices,
double line_width, const Rgba& rgba, bool line_segments) {
uuids::uuid_random_generator uuid_generator{generator_};
internal::SetObjectData data;
data.path = FullPath(path);
auto geometry = std::make_unique<internal::BufferGeometryData>();
geometry->uuid = uuids::to_string(uuid_generator());
geometry->position = vertices.cast<float>();
data.object.geometry = std::move(geometry);
auto material = std::make_unique<internal::MaterialData>();
material->uuid = uuids::to_string(uuid_generator());
material->type = "LineBasicMaterial";
material->color = ToMeshcatColor(rgba);
material->linewidth = line_width;
material->vertexColors = false;
data.object.material = std::move(material);
internal::MeshData mesh;
mesh.uuid = uuids::to_string(uuid_generator());
mesh.type = line_segments ? "LineSegments" : "Line";
mesh.geometry = data.object.geometry->uuid;
mesh.material = data.object.material->uuid;
data.object.object = std::move(mesh);
Defer([this, data = std::move(data)]() {
std::stringstream message_stream;
msgpack::pack(message_stream, data);
std::string message = message_stream.str();
app_->publish("all", message, uWS::OpCode::BINARY, false);
SceneTreeElement& e = scene_tree_root_[data.path];
e.object() = std::move(message);
});
}
// This function is public via the PIMPL.
void SetTriangleMesh(std::string_view path,
const Eigen::Ref<const Eigen::Matrix3Xd>& vertices,
const Eigen::Ref<const Eigen::Matrix3Xi>& faces,
const Rgba& rgba, bool wireframe,
double wireframe_line_width, SideOfFaceToRender side) {
DRAKE_DEMAND(IsThread(main_thread_id_));
uuids::uuid_random_generator uuid_generator{generator_};
internal::SetObjectData data;
data.path = FullPath(path);
auto geometry = std::make_unique<internal::BufferGeometryData>();
geometry->uuid = uuids::to_string(uuid_generator());
geometry->position = vertices.cast<float>();
geometry->faces = faces.cast<uint32_t>();
data.object.geometry = std::move(geometry);
auto material = std::make_unique<internal::MaterialData>();
material->uuid = uuids::to_string(uuid_generator());
material->type = "MeshPhongMaterial";
material->color = ToMeshcatColor(rgba);
material->transparent = (rgba.a() != 1.0);
material->opacity = rgba.a();
material->wireframe = wireframe;
material->wireframeLineWidth = wireframe_line_width;
material->vertexColors = false;
material->side = side;