Reputation: 19
I would like to record multiple meshcat visualizers with different prefix ids so I can eventually save them to an HTML file that I can interact with later. I would like the different visualizations to play on top of each other and to be able to select/unselect different visualizations.
Here is a minimal replication of the problem. I expect there to be two cartpole visualizations that are on top of each other. However, I only end up seeing one of them being recorded. The other cartpole seems stuck at the end position when I play back the recording
import meshcat
from pydrake.common import FindResourceOrThrow
from pydrake.multibody.plant import (
AddMultibodyPlantSceneGraph)
from pydrake.multibody.parsing import Parser
from pydrake.systems.analysis import Simulator
from pydrake.systems.framework import DiagramBuilder
from pydrake.systems.meshcat_visualizer import (
ConnectMeshcatVisualizer,
)
v = meshcat.Visualizer()
file_name = FindResourceOrThrow(
"drake/examples/multibody/cart_pole/cart_pole.sdf")
builder = DiagramBuilder()
cart_pole, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0)
Parser(plant=cart_pole).AddModelFromFile(file_name)
cart_pole.Finalize()
vis = ConnectMeshcatVisualizer(builder=builder,
prefix="vis",
scene_graph=scene_graph,
open_browser=False)
vis2 = ConnectMeshcatVisualizer(
builder=builder,
prefix="vis2",
scene_graph=scene_graph,
open_browser=False)
vis2.set_name("vis2")
diagram = builder.Build()
diagram_context = diagram.CreateDefaultContext()
cart_pole_context = diagram.GetMutableSubsystemContext(
cart_pole, diagram_context)
cart_pole.get_actuation_input_port().FixValue(cart_pole_context, .02)
simulator = Simulator(diagram, diagram_context)
simulator.set_publish_every_time_step(False)
vis.start_recording()
vis2.start_recording()
simulator.AdvanceTo(100)
vis.stop_recording()
vis2.stop_recording()
vis.publish_recording()
vis2.publish_recording()
# f = open("saved.html", "w")
# f.write(v.static_html())
# f.close()
Upvotes: 0
Views: 208
Reputation: 5533
Here is one solution. I don't love it, but it accomplishes the stated goal. Note the changes:
MultibodyPlant
with a distinct name for each simdelete_prefix_on_load=False
so it doesn't clear the old geometryimport meshcat
from pydrake.common import FindResourceOrThrow
from pydrake.multibody.plant import (AddMultibodyPlantSceneGraph)
from pydrake.multibody.parsing import Parser
from pydrake.systems.analysis import Simulator
from pydrake.systems.framework import DiagramBuilder
from pydrake.systems.meshcat_visualizer import (
ConnectMeshcatVisualizer,
)
animation = None
for i in range(3):
file_name = FindResourceOrThrow(
"drake/examples/multibody/cart_pole/cart_pole.sdf")
builder = DiagramBuilder()
cart_pole, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0)
Parser(plant=cart_pole).AddModelFromFile(file_name, f"plant{i}")
cart_pole.Finalize()
vis = ConnectMeshcatVisualizer(builder=builder,
scene_graph=scene_graph,
delete_prefix_on_load=False,
open_browser=False)
if animation:
vis._animation = animation
diagram = builder.Build()
diagram_context = diagram.CreateDefaultContext()
cart_pole_context = diagram.GetMutableSubsystemContext(
cart_pole, diagram_context)
cart_pole.get_actuation_input_port().FixValue(cart_pole_context, .02)
simulator = Simulator(diagram, diagram_context)
simulator.set_publish_every_time_step(False)
vis.start_recording()
simulator.AdvanceTo(10)
vis.stop_recording()
animation = vis._animation
vis.publish_recording()
Upvotes: 2