-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
Copy pathmeshcat_test.cc
1569 lines (1391 loc) · 59.5 KB
/
meshcat_test.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 <cstdlib>
#include <filesystem>
#include <thread>
#include <vector>
#include <fmt/format.h>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <msgpack.hpp>
#include "drake/common/find_resource.h"
#include "drake/common/temp_directory.h"
#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/common/test_utilities/expect_throws_message.h"
#include "drake/common/timer.h"
#include "drake/geometry/meshcat_types_internal.h"
namespace drake {
namespace geometry {
namespace {
namespace fs = std::filesystem;
using Eigen::Vector3d;
using math::RigidTransformd;
using math::RollPitchYawd;
using math::RotationMatrixd;
using testing::ElementsAre;
using ::testing::HasSubstr;
// A small wrapper around std::system to ensure correct argument passing.
int SystemCall(const std::vector<std::string>& argv) {
std::string command;
for (const std::string& arg : argv) {
// Note: Can't use ASSERT_THAT inside this subroutine.
EXPECT_THAT(arg, ::testing::Not(HasSubstr("'")));
command += fmt::format("'{}' ", arg);
}
return std::system(command.c_str());
}
// Calls a python helper program to send and receive websocket messages(s)
// to/from the given Meshcat instance.
//
// @param send_json Message to send, as a json string.
// @param expect_num_messages Expected number of messages to receive.
// @param expect_json Expected content of the final message, as a json string.
// @param expect_success Whether to insist that the python helper finished and
// the expected_json (if given) was actually received.
void CheckWebsocketCommand(const Meshcat& meshcat,
std::optional<std::string> send_json,
std::optional<int> expect_num_messages,
std::optional<std::string> expect_json,
bool expect_success = true) {
if (expect_num_messages) {
meshcat.Flush();
}
std::vector<std::string> argv;
argv.push_back(
FindResourceOrThrow("drake/geometry/meshcat_websocket_client"));
// Even when this unit test is itself running under valgrind, we don't want to
// instrument the helper process. Our valgrind configuration recognizes this
// argument and skips instrumentation of the child process.
argv.push_back("--disable-drake-valgrind-tracing");
argv.push_back(fmt::format("--ws_url={}", meshcat.ws_url()));
if (send_json) {
DRAKE_DEMAND(!send_json->empty());
argv.push_back(fmt::format("--send_message={}", std::move(*send_json)));
}
if (expect_num_messages) {
argv.push_back(
fmt::format("--expect_num_messages={}", *expect_num_messages));
}
if (expect_json) {
DRAKE_DEMAND(!expect_json->empty());
argv.push_back(fmt::format("--expect_message={}", std::move(*expect_json)));
}
argv.push_back(
fmt::format("--expect_success={}", expect_success ? "1" : "0"));
const int exit_code = SystemCall(argv);
if (expect_success) {
EXPECT_EQ(exit_code, 0);
}
}
/* Decodes the most recent SetTransform message for Meshcat on the given path
and returns the message's decoded path and transform data. If no message has
ever been sent, returns a default-constructed value. */
std::pair<std::string, Eigen::Matrix4d> GetDecodedTransform(
const Meshcat& meshcat, std::string_view path) {
std::string message = meshcat.GetPackedTransform(path);
if (message.empty()) {
return {};
}
msgpack::object_handle oh = msgpack::unpack(message.data(), message.size());
internal::SetTransformData decoded;
EXPECT_NO_THROW(decoded = oh.get().as<internal::SetTransformData>());
EXPECT_EQ(decoded.type, "set_transform");
Eigen::Map<Eigen::Matrix4d> matrix(decoded.matrix);
return {decoded.path, Eigen::Matrix4d{matrix}};
}
/* Decodes the most recent SetProperty message for Meshcat on the given path
and returns the message's decoded path and property value. If no message has
ever been sent, returns a default-constructed value. */
template <typename T>
std::pair<std::string, T> GetDecodedProperty(const Meshcat& meshcat,
std::string_view path,
std::string_view property) {
std::string message = meshcat.GetPackedProperty(path, std::string{property});
if (message.empty()) {
return {};
}
msgpack::object_handle oh = msgpack::unpack(message.data(), message.size());
internal::SetPropertyData<T> decoded;
EXPECT_NO_THROW(decoded = oh.get().as<internal::SetPropertyData<T>>());
EXPECT_EQ(decoded.type, "set_property");
EXPECT_EQ(decoded.property, property);
return {decoded.path, decoded.value};
}
GTEST_TEST(MeshcatTest, TestHttp) {
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(SystemCall({"/usr/bin/curl", "-o", "/dev/null", "--silent",
meshcat.web_url() + "/index.html"}),
0);
EXPECT_EQ(SystemCall({"/usr/bin/curl", "-o", "/dev/null", "--silent",
meshcat.web_url() + "/meshcat.js"}),
0);
EXPECT_EQ(SystemCall({"/usr/bin/curl", "-o", "/dev/null", "--silent",
meshcat.web_url() + "/favicon.ico"}),
0);
EXPECT_EQ(SystemCall({"/usr/bin/curl", "-o", "/dev/null", "--silent",
meshcat.web_url() + "/no-such-file"}),
0);
// Note that the pydrake visualizers_test.py case test_start_meshcat() also
// checks the http Content-Type and page data. It's too awkward to try to
// do that here.
}
GTEST_TEST(MeshcatTest, ConstructMultiple) {
Meshcat meshcat;
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());
}
// We'll assume that nothing else on the machine is using this port.
// This will have false positives if something else was using the port.
GTEST_TEST(MeshcatTest, HardCodedPort) {
// Use a port greater than 8000, to make sure the user can step outside our
// default range of [7000, 7999].
const int specific_port = 8422;
Meshcat meshcat(specific_port);
EXPECT_EQ(meshcat.port(), specific_port);
}
GTEST_TEST(MeshcatTest, DefaultPort) {
// The default constructor gets a default port.
Meshcat meshcat;
const int port = meshcat.port();
EXPECT_GE(port, 7000);
EXPECT_LE(port, 7999);
// Can't open the same port twice.
DRAKE_EXPECT_THROWS_MESSAGE(Meshcat(port),
"Meshcat failed to open a websocket port.");
}
GTEST_TEST(MeshcatTest, EphemeralPort) {
// Use port 0 to choose an ephemeral port:
// https://en.wikipedia.org/wiki/Ephemeral_port
Meshcat meshcat(0);
EXPECT_GE(meshcat.port(), 32768);
// Try clicking a button to make sure the number was correct. This also serves
// as an end-to-end test of button handling over websockets.
meshcat.AddButton("button");
CheckWebsocketCommand(meshcat, R"""({
"type": "button",
"name": "button"
})""",
{}, {});
EXPECT_EQ(meshcat.GetButtonClicks("button"), 1);
}
// Use a basic web_url_pattern to affect web_url() and ws_url(). The pattern
// parameter only affects those URLs getters, not the server's bind behavior.
GTEST_TEST(MeshcatTest, CustomHttp) {
const std::string pattern = "http://127.0.0.254:{port}";
const Meshcat meshcat({"", std::nullopt, pattern});
const std::string port = std::to_string(meshcat.port());
EXPECT_EQ(meshcat.web_url(), "http://127.0.0.254:" + port);
EXPECT_EQ(meshcat.ws_url(), "ws://127.0.0.254:" + port);
}
// Check a web_url_pattern that does not use any substitutions.
GTEST_TEST(MeshcatTest, CustomNoPort) {
const std::string pattern = "http://example.ngrok.io";
const Meshcat meshcat({"", std::nullopt, pattern});
EXPECT_EQ(meshcat.web_url(), "http://example.ngrok.io");
EXPECT_EQ(meshcat.ws_url(), "ws://example.ngrok.io");
}
// Check a web_url_pattern that uses https instead of http.
GTEST_TEST(MeshcatTest, CustomHttps) {
const std::string pattern = "https://localhost:{port}";
const Meshcat meshcat({"", std::nullopt, pattern});
const std::string port = std::to_string(meshcat.port());
EXPECT_EQ(meshcat.web_url(), "https://localhost:" + port);
EXPECT_EQ(meshcat.ws_url(), "wss://localhost:" + port);
}
// Check that binding to the don't-care host "" does not crash.
// It should display as "localhost".
GTEST_TEST(MeshcatTest, CustomDefaultInterface) {
const Meshcat meshcat({""});
const std::string port = std::to_string(meshcat.port());
EXPECT_EQ(meshcat.web_url(), "http://localhost:" + port);
}
// Check that binding to "*" (as mentioned in Params docs) does not crash.
// It should display as "localhost".
GTEST_TEST(MeshcatTest, CustomAllInterfaces) {
const Meshcat meshcat({"*"});
const std::string port = std::to_string(meshcat.port());
EXPECT_EQ(meshcat.web_url(), "http://localhost:" + port);
}
// Check that binding to an IP does not crash.
GTEST_TEST(MeshcatTest, CustomNumericInterface) {
const Meshcat meshcat({"127.0.0.1"});
const std::string port = std::to_string(meshcat.port());
EXPECT_EQ(meshcat.web_url(), "http://127.0.0.1:" + port);
}
// Check that binding to a malformed value does crash.
GTEST_TEST(MeshcatTest, BadCustomInterface) {
DRAKE_EXPECT_THROWS_MESSAGE(Meshcat({"----"}), ".*failed to open.*");
}
GTEST_TEST(MeshcatTest, MalformedCustom) {
// Using a non-existent substitution is detected immediately.
DRAKE_EXPECT_THROWS_MESSAGE(
Meshcat({"", std::nullopt, "http://localhost:{portnum}"}),
".*argument.*");
// Only http or https are allowed.
DRAKE_EXPECT_THROWS_MESSAGE(Meshcat({"", std::nullopt, "file:///tmp"}),
".*web_url_pattern.*http.*");
}
// Checks that unparsable messages are ignored.
GTEST_TEST(MeshcatTest, UnparseableMessageIgnored) {
auto dut = std::make_unique<Meshcat>();
// Send an unparsable message; don't expect a reply.
const char* const message = "0";
const bool expect_success = false;
CheckWebsocketCommand(*dut, message, {}, {}, expect_success);
// Pause to allow the websocket thread to run.
std::this_thread::sleep_for(std::chrono::milliseconds(100));
// The object can be destroyed with neither errors nor sanitizer leaks.
EXPECT_NO_THROW(dut.reset());
}
// Checks that parseable messages with unknown semantics are ignored.
GTEST_TEST(MeshcatTest, UnknownEventIgnored) {
auto dut = std::make_unique<Meshcat>();
// Send a syntactically well-formed UserInterfaceEvent to tickle the
// stack, but don't expect a reply.
const char* const message = R"""({
"type": "no_such_type",
"name": "no_such_name"
})""";
const bool expect_success = false;
CheckWebsocketCommand(*dut, message, {}, {}, expect_success);
// Pause to allow the websocket thread to run.
std::this_thread::sleep_for(std::chrono::milliseconds(100));
// The object can be destroyed with neither errors nor sanitizer leaks.
EXPECT_NO_THROW(dut.reset());
}
class MeshcatFaultTest : public testing::TestWithParam<int> {};
// Checks that a problem with the worker thread eventually ends up as an
// exception on the main thread.
TEST_P(MeshcatFaultTest, WorkerThreadFault) {
const int fault_number = GetParam();
auto dut = std::make_unique<Meshcat>();
// Cause the websocket thread to fail.
EXPECT_NO_THROW(dut->InjectWebsocketThreadFault(fault_number));
// Keep checking an accessor function until the websocket fault is detected
// and is converted into an exception on the main thread. Here we should be
// able to call *any* function and have it report the fault; we use web_url
// out of simplicity, and rely the impl() function in the cc file to prove
// that every public function is preceded by a ThrowIfWebsocketThreadExited.
auto checker = [&dut]() {
for (int i = 0; i < 10; ++i) {
// Send a syntactically well-formed UserInterfaceEvent to tickle the
// stack, but don't expect a reply.
const char* const message = R"""({
"type": "no_such_type",
"name": "no_such_name"
})""";
const bool expect_success = false;
CheckWebsocketCommand(*dut, message, {}, {}, expect_success);
// Poll the accessor function.
dut->web_url();
// Pause to allow the websocket thread to run.
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}
};
DRAKE_EXPECT_THROWS_MESSAGE(checker(), ".*thread exited.*");
// The object can be destroyed with neither errors nor sanitizer leaks.
EXPECT_NO_THROW(dut.reset());
}
INSTANTIATE_TEST_SUITE_P(AllFaults, MeshcatFaultTest,
testing::Range(0, Meshcat::kMaxFaultNumber + 1));
GTEST_TEST(MeshcatTest, NumActive) {
Meshcat meshcat;
EXPECT_EQ(meshcat.GetNumActiveConnections(), 0);
}
// Note: The Mesh shape is special. It can reference on-disk or in-memory data
// and they all need to be handled. This test runs through the various
// permutations.
GTEST_TEST(MeshcatTest, SetObjectWithMesh) {
Meshcat meshcat;
using testing::HasSubstr;
using testing::Not;
// A .obj file with material library and image. The packed message should
// encode the .obj, the .mtl file, and the image.
const fs::path obj_path =
FindResourceOrThrow("drake/geometry/render/test/meshes/rainbow_box.obj");
const Mesh disk_obj(obj_path, 0.25);
const auto obj_file = MemoryFile::Make(obj_path);
const auto mtl_file = MemoryFile::Make(
FindResourceOrThrow("drake/geometry/render/test/meshes/rainbow_box.mtl"));
const auto png_file = MemoryFile::Make(FindResourceOrThrow(
"drake/geometry/render/test/meshes/rainbow_stripes.png"));
const Mesh memory_obj(InMemoryMesh{
MemoryFile(obj_file.contents(), obj_file.extension(),
"a hint; *not* a path"),
{{"rainbow_box.mtl", MemoryFile(mtl_file)},
{"rainbow_stripes.png", MemoryFile(png_file)}}});
// The "hetero" objs mix up the supporting files so that, in turn, one is
// in memory, and one is on-disk.
const Mesh hetero_obj1(InMemoryMesh{
MemoryFile(obj_file.contents(), obj_file.extension(), "hetero1_obj"),
{{"rainbow_box.mtl", fs::path(mtl_file.filename_hint())},
{"rainbow_stripes.png", MemoryFile(png_file)}}});
const Mesh hetero_obj2(InMemoryMesh{
MemoryFile(obj_file.contents(), obj_file.extension(), "hetero2_obj"),
{{"rainbow_box.mtl", MemoryFile(mtl_file)},
{"rainbow_stripes.png", fs::path(png_file.filename_hint())}}});
for (const auto* mesh_ptr :
{&disk_obj, &memory_obj, &hetero_obj1, &hetero_obj2}) {
const MeshSource& source = mesh_ptr->source();
const bool is_disk = source.is_path();
SCOPED_TRACE(fmt::format("Full obj from {} - {}",
is_disk ? "disk" : "memory",
is_disk ? std::string() : source.description()));
DRAKE_DEMAND(meshcat.GetPackedObject("obj_path").empty());
meshcat.SetObject("obj_path", *mesh_ptr);
const std::string packed_obj = meshcat.GetPackedObject("obj_path");
EXPECT_FALSE(packed_obj.empty());
// Evidence that the image got loaded.
EXPECT_THAT(packed_obj, testing::HasSubstr("data:image/png;base64"));
// Evidence that the material library got loaded.
EXPECT_THAT(packed_obj, testing::HasSubstr("newmtl Rainbow_Stripes"));
meshcat.Delete("obj_path");
ASSERT_TRUE(meshcat.GetPackedObject("obj_path").empty());
}
// Missing elements from the in-memory mesh should proceed (but with missing
// resources). Warnings are also spewed, but we can't test for those.
// Missing the mtl file (whether the png is present or not), means no mtl and
// no png.
for (const InMemoryMesh& mem_mesh :
{InMemoryMesh{obj_file},
InMemoryMesh{obj_file,
{{"rainbow_stripes.png", MemoryFile(png_file)}}}}) {
SCOPED_TRACE(fmt::format("Partial OBJ with {} supporting files",
mem_mesh.supporting_files.size()));
DRAKE_DEMAND(meshcat.GetPackedObject("obj_path").empty());
meshcat.SetObject("obj_path", Mesh(mem_mesh));
const std::string packed_obj = meshcat.GetPackedObject("obj_path");
EXPECT_FALSE(packed_obj.empty());
EXPECT_THAT(packed_obj, Not(HasSubstr("data:image/png;base64")));
EXPECT_THAT(packed_obj, Not(HasSubstr("newmtl Rainbow_Stripes")));
meshcat.Delete("obj_path");
}
// If only the texture is missing, we still have "success" - materials are
// loaded but the image is not.
{
DRAKE_DEMAND(meshcat.GetPackedObject("obj_path").empty());
meshcat.SetObject("obj_path",
Mesh(InMemoryMesh{obj_file, {{"rainbow_box.mtl",
MemoryFile(mtl_file)}}}));
const std::string packed_obj = meshcat.GetPackedObject("obj_path");
EXPECT_FALSE(packed_obj.empty());
EXPECT_THAT(packed_obj, Not(HasSubstr("data:image/png;base64")));
EXPECT_THAT(packed_obj, HasSubstr("newmtl Rainbow_Stripes"));
meshcat.Delete("obj_path");
}
// Meshcat defers to `meshcat_internal` logic for handling glTF files so
// it's enough to show that good things happen. Tests on the internal
// implementations are responsible for confirming it's the *right* thing.
meshcat.SetObject(
"gltf",
Mesh(FindResourceOrThrow("drake/geometry/render/test/meshes/cube1.gltf"),
0.25));
EXPECT_FALSE(meshcat.GetPackedObject("gltf").empty());
}
// The correctness of this is established with meshcat_manual_test. Here we
// simply aim to provide code coverage for CI (e.g., no segfaults).
// Meshes are treated in SetObjectWithMesh.
GTEST_TEST(MeshcatTest, SetObjectWithShape) {
Meshcat meshcat;
EXPECT_TRUE(meshcat.GetPackedObject("sphere").empty());
meshcat.SetObject("sphere", Sphere(0.25), Rgba(1.0, 0, 0, 1));
EXPECT_FALSE(meshcat.GetPackedObject("sphere").empty());
meshcat.SetObject("cylinder", Cylinder(0.25, 0.5), Rgba(0.0, 1.0, 0, 1));
EXPECT_FALSE(meshcat.GetPackedObject("cylinder").empty());
// HalfSpaces are not supported yet; this should only log a warning.
meshcat.SetObject("halfspace", HalfSpace());
EXPECT_TRUE(meshcat.GetPackedObject("halfspace").empty());
meshcat.SetObject("box", Box(0.25, 0.25, 0.5), Rgba(0, 0, 1, 1));
EXPECT_FALSE(meshcat.GetPackedObject("box").empty());
meshcat.SetObject("ellipsoid", Ellipsoid(0.25, 0.25, 0.5),
Rgba(1.0, 0, 1, 1));
EXPECT_FALSE(meshcat.GetPackedObject("ellipsoid").empty());
meshcat.SetObject("capsule", Capsule(0.25, 0.5));
EXPECT_FALSE(meshcat.GetPackedObject("capsule").empty());
meshcat.SetObject(
"convex",
Convex(FindResourceOrThrow("drake/geometry/render/test/meshes/box.obj"),
0.25));
EXPECT_FALSE(meshcat.GetPackedObject("convex").empty());
// Bad filename (no extension). Should only log a warning.
meshcat.SetObject("bad", Mesh("test"));
EXPECT_TRUE(meshcat.GetPackedObject("bad").empty());
// Bad filename (file doesn't exist). Should only log a warning.
meshcat.SetObject("bad", Mesh("test.obj"));
EXPECT_TRUE(meshcat.GetPackedObject("bad").empty());
}
// Confirms that an OBJ with a missing material becomes a MeshData instead of a
// MeshfileObjectData.
GTEST_TEST(MeshcatTest, ObjWithMissingMtl) {
Meshcat meshcat;
// The baseline .obj with .mtl file.
const std::string obj_source =
FindResourceOrThrow("drake/geometry/render/test/meshes/box.obj");
meshcat.SetObject("with_mtl", Mesh(obj_source), Rgba(1, 0, 1));
const std::string with_mtl_packed = meshcat.GetPackedObject("with_mtl");
EXPECT_THAT(with_mtl_packed, testing::HasSubstr("_meshfile_object"));
EXPECT_THAT(with_mtl_packed, testing::HasSubstr("mtl_library"));
// Copy the .obj into a directory, without its .mtl file.
const fs::path dir = temp_directory();
const fs::path missing_mtl_path = dir / "box.obj";
fs::copy_file(obj_source, missing_mtl_path);
meshcat.SetObject("missing_mtl", Mesh(missing_mtl_path.string()),
Rgba(1, 0.75, 0.5));
const std::string missing_mtl_packed = meshcat.GetPackedObject("missing_mtl");
EXPECT_THAT(missing_mtl_packed, testing::HasSubstr("_meshfile_geometry"));
EXPECT_THAT(missing_mtl_packed, testing::HasSubstr("MeshPhongMaterial"));
// The Rgba value above gets hex encoded as follows:
EXPECT_THAT(missing_mtl_packed, testing::HasSubstr("\0\xFF\xBF\x7F"));
}
GTEST_TEST(MeshcatTest, SetObjectWithPointCloud) {
Meshcat meshcat;
perception::PointCloud cloud(5);
// clang-format off
cloud.mutable_xyzs().transpose() <<
1, 2, 3,
10, 20, 30,
100, 200, 300,
4, 5, 6,
40, 50, 60;
// clang-format on
meshcat.SetObject("cloud", cloud);
EXPECT_FALSE(meshcat.GetPackedObject("cloud").empty());
perception::PointCloud rgb_cloud(
5, perception::pc_flags::kXYZs | perception::pc_flags::kRGBs);
rgb_cloud.mutable_xyzs() = cloud.xyzs();
// clang-format off
rgb_cloud.mutable_rgbs() <<
1, 2, 3,
10, 20, 30,
100, 200, 255,
4, 5, 6,
40, 50, 60;
// clang-format on
meshcat.SetObject("rgb_cloud", rgb_cloud);
EXPECT_FALSE(meshcat.GetPackedObject("rgb_cloud").empty());
}
GTEST_TEST(MeshcatTest, SetObjectWithTriangleSurfaceMesh) {
Meshcat meshcat;
const int face_data[2][3] = {{0, 1, 2}, {2, 3, 0}};
std::vector<SurfaceTriangle> faces;
for (int f = 0; f < 2; ++f) faces.emplace_back(face_data[f]);
const Eigen::Vector3d vertex_data[4] = {
{0, 0, 0}, {0.5, 0, 0}, {0.5, 0.5, 0}, {0, 0.5, 0.5}};
std::vector<Eigen::Vector3d> vertices;
for (int v = 0; v < 4; ++v) vertices.emplace_back(vertex_data[v]);
TriangleSurfaceMesh<double> surface_mesh(std::move(faces),
std::move(vertices));
meshcat.SetObject("triangle_mesh", surface_mesh, Rgba(0.9, 0, 0.9, 1.0));
EXPECT_FALSE(meshcat.GetPackedObject("triangle_mesh").empty());
meshcat.SetObject("triangle_mesh_wireframe", surface_mesh,
Rgba(0.9, 0, 0.9, 1.0), true, 5.0);
EXPECT_FALSE(meshcat.GetPackedObject("triangle_mesh_wireframe").empty());
}
GTEST_TEST(MeshcatTest, PlotSurface) {
Meshcat meshcat;
constexpr int nx = 15, ny = 11;
Eigen::MatrixXd X = RowVector<double, nx>::LinSpaced(0, 1).replicate<ny, 1>();
Eigen::MatrixXd Y = Vector<double, ny>::LinSpaced(0, 1).replicate<1, nx>();
// z = y*sin(5*x)
Eigen::MatrixXd Z = (Y.array() * (5 * X.array()).sin()).matrix();
// Wireframe = false.
meshcat.PlotSurface("plot_surface", X, Y, Z, Rgba(0, 0, 0.9, 1.0), false);
EXPECT_FALSE(meshcat.GetPackedObject("plot_surface").empty());
// Wireframe = true.
meshcat.PlotSurface("plot_surface_wireframe", X, Y, Z, Rgba(0, 0, 0.9, 1.0),
true);
EXPECT_FALSE(meshcat.GetPackedObject("plot_surface_wireframe").empty());
}
GTEST_TEST(MeshcatTest, SetLine) {
Meshcat meshcat;
Eigen::Matrix3Xd vertices(3, 200);
Eigen::RowVectorXd t = Eigen::RowVectorXd::LinSpaced(200, 0, 10 * M_PI);
vertices << 0.25 * t.array().sin(), 0.25 * t.array().cos(), t / (10 * M_PI);
meshcat.SetLine("line", vertices, 3.0, Rgba(0, 0, 1, 1));
EXPECT_FALSE(meshcat.GetPackedObject("line").empty());
Eigen::Matrix3Xd start(3, 4), end(3, 4);
// clang-format off
start << -0.1, -0.1, 0.1, 0.1,
-0.1, 0.1, -0.1, 0.1,
0, 0, 0, 0;
// clang-format on
end = start;
end.row(2) = Eigen::RowVector4d::Ones();
meshcat.SetLineSegments("line_segments", start, end, 5.0, Rgba(0, 1, 0, 1));
EXPECT_FALSE(meshcat.GetPackedObject("line_segments").empty());
// Throws if start.cols() != end.cols().
EXPECT_THROW(
meshcat.SetLineSegments("bad_segments", Eigen::Matrix3Xd::Identity(3, 4),
Eigen::Matrix3Xd::Identity(3, 3)),
std::exception);
}
GTEST_TEST(MeshcatTest, SetTriangleMesh) {
Meshcat meshcat;
// Populate the vertices/faces transposed, for easier Eigen initialization.
Eigen::MatrixXd vertices(4, 3);
Eigen::MatrixXi faces(2, 3);
// clang-format off
vertices << 0, 0, 0,
1, 0, 0,
1, 0, 1,
0, 0, 1;
faces << 0, 1, 2,
3, 0, 2;
// clang-format on
meshcat.SetTriangleMesh("triangle_mesh", vertices.transpose(),
faces.transpose(), Rgba(1, 0, 0, 1), true, 5.0);
EXPECT_FALSE(meshcat.GetPackedObject("triangle_mesh").empty());
}
GTEST_TEST(MeshcatTest, SetTransform) {
Meshcat meshcat;
EXPECT_FALSE(meshcat.HasPath("frame"));
EXPECT_TRUE(meshcat.GetPackedTransform("frame").empty());
const RigidTransformd X_ParentPath{RollPitchYawd(0.5, 0.26, -3),
Vector3d{0.9, -2.0, 0.12}};
meshcat.SetTransform("frame", X_ParentPath);
const auto [actual_path, actual_value] =
GetDecodedTransform(meshcat, "frame");
EXPECT_EQ(actual_path, "/drake/frame");
EXPECT_TRUE(CompareMatrices(actual_value, X_ParentPath.GetAsMatrix4()));
}
GTEST_TEST(MeshcatTest, SetTransformWithMatrix) {
Meshcat meshcat;
EXPECT_FALSE(meshcat.HasPath("frame"));
EXPECT_TRUE(meshcat.GetPackedTransform("frame").empty());
Eigen::Matrix4d matrix;
// clang-format off
matrix << 1, 2, 3, 4,
5, 6, 7, 8,
-1, -2, -3, -4,
-5, -6, -7, -8;
// clang-format on
meshcat.SetTransform("frame", matrix);
const auto [actual_path, actual_value] =
GetDecodedTransform(meshcat, "frame");
EXPECT_EQ(actual_path, "/drake/frame");
EXPECT_TRUE(CompareMatrices(actual_value, matrix));
}
GTEST_TEST(MeshcatTest, Delete) {
Meshcat meshcat;
// Ok to delete an empty tree.
meshcat.Delete();
EXPECT_FALSE(meshcat.HasPath(""));
EXPECT_FALSE(meshcat.HasPath("frame"));
meshcat.SetTransform("frame", RigidTransformd{});
EXPECT_TRUE(meshcat.HasPath(""));
EXPECT_TRUE(meshcat.HasPath("frame"));
EXPECT_TRUE(meshcat.HasPath("/drake/frame"));
// Deleting a random string does nothing.
meshcat.Delete("bad");
EXPECT_TRUE(meshcat.HasPath("frame"));
meshcat.Delete("frame");
EXPECT_FALSE(meshcat.HasPath("frame"));
// Deleting a parent directory deletes all children.
meshcat.SetTransform("test/frame", RigidTransformd{});
meshcat.SetTransform("test/frame2", RigidTransformd{});
meshcat.SetTransform("test/another/frame", RigidTransformd{});
EXPECT_TRUE(meshcat.HasPath("test/frame"));
EXPECT_TRUE(meshcat.HasPath("test/frame2"));
EXPECT_TRUE(meshcat.HasPath("test/another/frame"));
meshcat.Delete("test");
EXPECT_FALSE(meshcat.HasPath("test/frame"));
EXPECT_FALSE(meshcat.HasPath("test/frame2"));
EXPECT_FALSE(meshcat.HasPath("test/another/frame"));
EXPECT_TRUE(meshcat.HasPath("/drake"));
// Deleting the empty string deletes the prefix.
meshcat.SetTransform("test/frame", RigidTransformd{});
meshcat.SetTransform("test/frame2", RigidTransformd{});
meshcat.SetTransform("test/another/frame", RigidTransformd{});
EXPECT_TRUE(meshcat.HasPath("test/frame"));
EXPECT_TRUE(meshcat.HasPath("test/frame2"));
EXPECT_TRUE(meshcat.HasPath("test/another/frame"));
meshcat.Delete();
EXPECT_FALSE(meshcat.HasPath("test/frame"));
EXPECT_FALSE(meshcat.HasPath("test/frame2"));
EXPECT_FALSE(meshcat.HasPath("test/another/frame"));
EXPECT_FALSE(meshcat.HasPath("/drake"));
}
// Tests three methods of SceneTreeElement:
// - SceneTreeElement::operator[]() is used in Meshcat::Set*(). We'll use
// SetTransform() here.
// - SceneTreeElement::Find() is used in Meshcat::HasPath() and
// Meshcat::GetPacked*(). We'll use HasPath() to test.
// - SceneTreeElement::Delete() is used in Meshat::Delete().
// All of them also run through WebSocketPublisher::FullPath().
GTEST_TEST(MeshcatTest, Paths) {
Meshcat meshcat;
// Absolute paths.
meshcat.SetTransform("/foo/frame", RigidTransformd{});
EXPECT_TRUE(meshcat.HasPath("/foo/frame"));
meshcat.Delete("/foo/frame");
EXPECT_FALSE(meshcat.HasPath("/foo/frame"));
// Absolute paths with strange spellings.
meshcat.SetTransform("///bar///frame///", RigidTransformd{});
EXPECT_TRUE(meshcat.HasPath("//bar//frame//"));
EXPECT_TRUE(meshcat.HasPath("/bar/frame"));
meshcat.Delete("////bar//frame///");
EXPECT_FALSE(meshcat.HasPath("/bar/frame"));
// Relative paths.
meshcat.SetTransform("frame", RigidTransformd{});
EXPECT_TRUE(meshcat.HasPath("frame"));
EXPECT_TRUE(meshcat.HasPath("/drake/frame"));
// Relative paths with strange spellings.
meshcat.SetTransform("bar///frame///", RigidTransformd{});
EXPECT_TRUE(meshcat.HasPath("bar//frame//"));
EXPECT_TRUE(meshcat.HasPath("/drake/bar/frame"));
meshcat.Delete("bar//frame//");
EXPECT_FALSE(meshcat.HasPath("bar/frame"));
EXPECT_FALSE(meshcat.HasPath("/drake/bar/frame"));
}
GTEST_TEST(MeshcatTest, SetPropertyBool) {
Meshcat meshcat;
const std::string path{"/Grid"};
const std::string property{"visible"};
EXPECT_FALSE(meshcat.HasPath(path));
EXPECT_TRUE(meshcat.GetPackedProperty(path, property).empty());
meshcat.SetProperty(path, property, false);
EXPECT_TRUE(meshcat.HasPath(path));
const auto [actual_path, actual_value] =
GetDecodedProperty<bool>(meshcat, path, property);
EXPECT_EQ(actual_path, path);
EXPECT_FALSE(actual_value);
}
GTEST_TEST(MeshcatTest, SetPropertyDouble) {
Meshcat meshcat;
const std::string path{"/Cameras/default/rotated/<object>"};
const std::string property{"zoom"};
EXPECT_FALSE(meshcat.HasPath(path));
EXPECT_TRUE(meshcat.GetPackedProperty(path, property).empty());
meshcat.SetProperty(path, property, 2.0);
EXPECT_TRUE(meshcat.HasPath(path));
const auto [actual_path, actual_value] =
GetDecodedProperty<double>(meshcat, path, property);
EXPECT_EQ(actual_path, path);
EXPECT_EQ(actual_value, 2.0);
}
GTEST_TEST(MeshcatTest, SetEnvironmentMap) {
Meshcat meshcat;
const std::string path{"/Background/<object>"};
const std::string property{"environment_map"};
EXPECT_FALSE(meshcat.HasPath(path));
auto [actual_path, actual_value] =
GetDecodedProperty<std::string>(meshcat, path, property);
EXPECT_EQ(actual_path, "");
EXPECT_EQ(actual_value, "");
// Set the map to a valid image.
const fs::path env_map(
FindResourceOrThrow("drake/geometry/test/env_256_cornell_box.png"));
EXPECT_NO_THROW(meshcat.SetEnvironmentMap(env_map));
EXPECT_TRUE(meshcat.HasPath(path));
std::tie(actual_path, actual_value) =
GetDecodedProperty<std::string>(meshcat, path, property);
EXPECT_EQ(actual_path, path);
EXPECT_THAT(actual_value, testing::StartsWith("cas-"));
// Clear the map with an empty string.
EXPECT_NO_THROW(meshcat.SetEnvironmentMap(""));
EXPECT_TRUE(meshcat.HasPath(path));
std::tie(actual_path, actual_value) =
GetDecodedProperty<std::string>(meshcat, path, property);
EXPECT_EQ(actual_path, path);
EXPECT_EQ(actual_value, "");
// An invalid map throws.
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.SetEnvironmentMap("invalid_file.png"),
".*invalid_file.png.*environment_map.*");
}
GTEST_TEST(MeshcatTest, InitialPropeties) {
// Construct Meshcat with some extra initial properties.
const std::vector<double> some_vector{1.0, 2.0};
const std::string some_string{"hello"};
const bool some_bool{true};
const double some_double{22.2};
const Meshcat meshcat{MeshcatParams{
.initial_properties = {
{.path = "/a", .property = "p1", .value = some_vector},
{.path = "/b", .property = "p2", .value = some_string},
{.path = "/c", .property = "p3", .value = some_bool},
{.path = "/d", .property = "p4", .value = some_double},
},
}};
// Check that they all showed up.
auto check_property = [&meshcat](auto path, auto property, auto value) {
SCOPED_TRACE(fmt::format("property = {}", property));
using T = decltype(value);
const auto [actual_path, actual_value] =
GetDecodedProperty<T>(meshcat, path, property);
EXPECT_EQ(actual_path, path);
EXPECT_EQ(actual_value, value);
};
check_property("/a", "p1", some_vector);
check_property("/b", "p2", some_string);
check_property("/c", "p3", some_bool);
check_property("/d", "p4", some_double);
}
// Tests the functional logic of button handling, without actually creating any
// websocket connections. (The EphemeralPort case tests a button using an actual
// connection.)
GTEST_TEST(MeshcatTest, Buttons) {
Meshcat meshcat;
// Asking for clicks prior to adding is an error.
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.GetButtonClicks("alice"),
"Meshcat does not have any button named alice.*");
// A new button starts out unclicked.
meshcat.AddButton("alice");
EXPECT_EQ(meshcat.GetButtonClicks("alice"), 0);
auto click = [&meshcat]() {
internal::UserInterfaceEvent data;
data.type = "button";
data.name = "alice";
std::stringstream message_stream;
msgpack::pack(message_stream, data);
meshcat.InjectWebsocketMessage(message_stream.str());
};
// Clicking the button increases the count.
click();
EXPECT_EQ(meshcat.GetButtonClicks("alice"), 1);
// Adding using an existing button name resets its count.
meshcat.AddButton("alice");
EXPECT_EQ(meshcat.GetButtonClicks("alice"), 0);
// Clicking the button increases the count again.
click();
EXPECT_EQ(meshcat.GetButtonClicks("alice"), 1);
// Removing the button then asking for clicks is an error.
meshcat.DeleteButton("alice");
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.GetButtonClicks("alice"),
"Meshcat does not have any button named alice.*");
// Strictly (the default) removing a missing button throws.
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.DeleteButton("alice"),
"Meshcat does not have any button named alice.*");
// Non-strictly removing a non-existent button issues a warning. Not tested
// here; see console output.
EXPECT_FALSE(meshcat.DeleteButton("alice", /*strict = */false));
// Adding the button anew starts with a zero count again.
meshcat.AddButton("alice");
EXPECT_EQ(meshcat.GetButtonClicks("alice"), 0);
// Buttons are removed when deleting all controls.
meshcat.AddButton("bob");
meshcat.DeleteAddedControls();
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.GetButtonClicks("alice"),
"Meshcat does not have any button named alice.*");
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.GetButtonClicks("bob"),
"Meshcat does not have any button named bob.*");
// Adding a button with the keycode.
meshcat.AddButton("alice", "KeyT");
click();
EXPECT_EQ(meshcat.GetButtonClicks("alice"), 1);
// Adding with the same keycode still resets.
meshcat.AddButton("alice", "KeyT");
EXPECT_EQ(meshcat.GetButtonClicks("alice"), 0);
// Adding the same button with an empty keycode throws.
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.AddButton("alice"),
".*does not match the current keycode.*");
// Adding the same button with a different keycode throws.
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.AddButton("alice", "KeyR"),
".*does not match the current keycode.*");
meshcat.DeleteButton("alice");
// Adding a button with the keycode empty, then populated works.
meshcat.AddButton("alice");
meshcat.AddButton("alice", "KeyT");
}
GTEST_TEST(MeshcatTest, Sliders) {
Meshcat meshcat;
DRAKE_EXPECT_THROWS_MESSAGE(
meshcat.GetSliderValue("slider"),
"Meshcat does not have any slider named slider.*");
meshcat.AddSlider("slider", 0.2, 1.5, 0.1, 0.5);
EXPECT_NEAR(meshcat.GetSliderValue("slider"), 0.5, 1e-14);
meshcat.SetSliderValue("slider", 0.7);
EXPECT_NEAR(meshcat.GetSliderValue("slider"), 0.7, 1e-14);
meshcat.SetSliderValue("slider", -2.0);
EXPECT_NEAR(meshcat.GetSliderValue("slider"), 0.2, 1e-14);
meshcat.SetSliderValue("slider", 2.0);
EXPECT_NEAR(meshcat.GetSliderValue("slider"), 1.5, 1e-14);
meshcat.SetSliderValue("slider", 1.245);
EXPECT_NEAR(meshcat.GetSliderValue("slider"), 1.2, 1e-14);
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.AddSlider("slider", 0.2, 1.5, 0.1, 0.5),
"Meshcat already has a slider named slider.");
EXPECT_TRUE(meshcat.DeleteSlider("slider"));
DRAKE_EXPECT_THROWS_MESSAGE(
meshcat.GetSliderValue("slider"),
"Meshcat does not have any slider named slider.*");
meshcat.AddSlider("slider1", 2, 3, 0.01, 2.35);
meshcat.AddSlider("slider2", 4, 5, 0.01, 4.56);
auto slider_names = meshcat.GetSliderNames();
EXPECT_THAT(slider_names, ElementsAre("slider1", "slider2"));
meshcat.DeleteAddedControls();
DRAKE_EXPECT_THROWS_MESSAGE(
meshcat.GetSliderValue("slider1"),
"Meshcat does not have any slider named slider1.*");
DRAKE_EXPECT_THROWS_MESSAGE(
meshcat.GetSliderValue("slider2"),
"Meshcat does not have any slider named slider2.*");
// Strictly (the default) removing a missing slider throws.
DRAKE_EXPECT_THROWS_MESSAGE(
meshcat.DeleteSlider("slider1"),
"Meshcat does not have any slider named slider1.*");
// Non-strictly removing a non-existent slider issues a warning. Not tested
// here; see console output.
EXPECT_FALSE(meshcat.DeleteSlider("slider1", /*strict = */false));
slider_names = meshcat.GetSliderNames();
EXPECT_EQ(slider_names.size(), 0);
}
GTEST_TEST(MeshcatTest, DuplicateMixedControls) {
Meshcat meshcat;
meshcat.AddButton("button");
meshcat.AddSlider("slider", 0.2, 1.5, 0.1, 0.5);
// We cannot use AddButton nor AddSlider to change the type of an existing
// control by attempting to re-use its name.
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.AddButton("slider"),
"Meshcat already has a slider named slider.");
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.AddButton("slider", "KeyR"),
"Meshcat already has a slider named slider.");
DRAKE_EXPECT_THROWS_MESSAGE(meshcat.AddSlider("button", 0.2, 1.5, 0.1, 0.5),
"Meshcat already has a button named button.");
}
// Properly testing Meshcat's limited support for gamepads requires human
// input, and is done in meshcat_manual_test. This test simply ensures the
// entry point forwards along the Javascript messages.
GTEST_TEST(MeshcatTest, Gamepad) {
Meshcat meshcat;
Meshcat::Gamepad gamepad = meshcat.GetGamepad();
// Check the default status assuming no messages have been received:
EXPECT_FALSE(gamepad.index);
EXPECT_TRUE(gamepad.button_values.empty());
EXPECT_TRUE(gamepad.axes.empty());
// Clicking the button increases the count.
CheckWebsocketCommand(meshcat, R"""({
"type": "gamepad",
"name": "",
"gamepad": {
"index": 1,
"button_values": [0, 0.5],
"axes": [0.1, 0.2, 0.3, 0.4]
}
})""",
{}, {});
gamepad = meshcat.GetGamepad();
EXPECT_TRUE(gamepad.index);
EXPECT_EQ(gamepad.index, 1);
std::vector<double> expected_button_values{0, 0.5};