From 9702aed0fbe357295a9ccd5c0f6c2d8a9550076b Mon Sep 17 00:00:00 2001 From: Robin Deits Date: Mon, 19 Mar 2018 16:00:10 -0400 Subject: [PATCH] overload open() and wait() for mechvis --- src/visualizer.jl | 4 +++- test/runtests.jl | 8 ++++---- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/src/visualizer.jl b/src/visualizer.jl index 9ff4af4..488e0c0 100644 --- a/src/visualizer.jl +++ b/src/visualizer.jl @@ -66,4 +66,6 @@ function rbd.set_configuration!(mvis::MechanismVisualizer, args...) _render_state!(mvis) end -MeshCat.IJuliaCell(mvis::MechanismVisualizer) = MeshCat.IJuliaCell(mvis.visualizer) \ No newline at end of file +MeshCat.IJuliaCell(mvis::MechanismVisualizer) = MeshCat.IJuliaCell(mvis.visualizer) +Base.open(mvis::MechanismVisualizer) = open(mvis.visualizer) +Base.wait(mvis::MechanismVisualizer) = wait(mvis.visualizer) diff --git a/test/runtests.jl b/test/runtests.jl index 3e90e55..4ef6bec 100644 --- a/test/runtests.jl +++ b/test/runtests.jl @@ -8,16 +8,16 @@ using ValkyrieRobot using NBInclude vis = Visualizer() -if !haskey(ENV, "CI") - open(vis) - wait(vis) -end @testset "MeshCatMechanisms" begin @testset "URDF mechanism" begin urdf = joinpath(@__DIR__, "urdf", "Acrobot.urdf") robot = parse_urdf(Float64, urdf) mvis = MechanismVisualizer(robot, URDFVisuals(urdf), vis) + if !haskey(ENV, "CI") + open(mvis) + wait(mvis) + end set_configuration!(mvis, [1.0, -0.5]) @testset "simulation and animation" begin