Skip to content

Commit

Permalink
Merge pull request #38 from EricCousineau-TRI/feature-meshcat_on_binder
Browse files Browse the repository at this point in the history
meshcat_on_binder: Suggested fixes
  • Loading branch information
RussTedrake authored Jun 9, 2020
2 parents 961b902 + 768c211 commit db3a546
Show file tree
Hide file tree
Showing 2 changed files with 35 additions and 20 deletions.
48 changes: 31 additions & 17 deletions bindings/pydrake/systems/meshcat_visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -250,8 +250,10 @@ def __init__(self,
self.set_name('meshcat_visualizer')
self.DeclarePeriodicPublish(draw_period, 0.0)
self.draw_period = draw_period
self.reset_recording()

# Recording.
self._is_recording = False
self.reset_recording()

# Pose bundle (from SceneGraph) input port.
# TODO(tehbelinda): Rename the `lcm_visualization` port to match
Expand Down Expand Up @@ -382,41 +384,53 @@ def DoPublish(self, context, event):
# The MBP parsers only register the plant as a nameless source.
# TODO(russt): Use a more textual naming convention here?
pose_matrix = pose_bundle.get_transform(frame_i)
self.vis[self.prefix][source_name][str(model_id)][frame_name]\
.set_transform(pose_matrix.GetAsMatrix4())
cur_vis = (
self.vis[self.prefix][source_name][str(model_id)][frame_name])
cur_vis.set_transform(pose_matrix.GetAsMatrix4())
if self._is_recording:
with self._animation.at_frame(
self.vis[self.prefix][source_name][str(model_id)]
[frame_name], self._recording_frame_num) as frame:
frame.set_transform(pose_matrix.GetAsMatrix4())
self._recording_frame_num += 1
cur_vis, self._recording_frame_num) as cur_vis_frame:
cur_vis_frame.set_transform(pose_matrix.GetAsMatrix4())

if self._is_recording:
self._recording_frame_num += 1

def start_recording(self):
"""
Sets a flag to record future publish events as animation frames.
Note: This syntax was chosen to match PyPlotVisualizer.
Precondition:
This must not be recording.
"""
# N.B. This recording API is intended to match PyPlotVisualizer's.
assert not self._is_recording, "Must NOT be recording"
self._is_recording = True

def stop_recording(self):
"""
Sets a flag to record future publish events as animation frames.
Note: This syntax was chosen to match PyPlotVisualizer.
"""
self._is_recording = False
Stops recording and publishes animation to ``meshcat.Visualizer``.
def publish_recording(self):
"""
Publish any recorded animation to Meshcat. Use the controls dialog
in the browser to review it.
This animation can be seen using `self.vis.render_static()`, and you
can browse the animation using meshcat's controls in the browser
widget, under "Animations > default".
Precondition:
This must be recording.
"""
# N.B. This recording API is intended to match PyPlotVisualizer's.
assert self._is_recording, "Must be recording"
self._is_recording = False
self.vis.set_animation(self._animation)

def reset_recording(self):
"""
Resets all recorded data.
Note: This syntax was chosen to match PyPlotVisualizer.
Precondition:
This must not be recording.
"""
# N.B. This recording API is intended to match PyPlotVisualizer's.
assert not self._is_recording, "Must NOT be recording"
self._animation = Animation(default_framerate=1./self.draw_period)
self._recording_frame_num = 0

Expand Down
7 changes: 4 additions & 3 deletions tutorials/rendering_multibody_plant.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -434,6 +434,7 @@
"outputs": [],
"source": [
"# Set the context to make the simulation valid and slightly interesting.\n",
"simulator.get_mutable_context().SetTime(.0)\n",
"plant_context = plant.GetMyContextFromRoot(simulator.get_mutable_context())\n",
"plant.get_actuation_input_port(iiwa_1).FixValue(plant_context, np.zeros((7,1)))\n",
"plant.get_actuation_input_port(iiwa_2).FixValue(plant_context, np.zeros((7,1)))\n",
Expand All @@ -444,10 +445,10 @@
"\n",
"# Start recording and simulate.\n",
"meshcat_vis.start_recording()\n",
"simulator.AdvanceTo(simulator.get_context().get_time() + 1.0)\n",
"simulator.AdvanceTo(1.0)\n",
"\n",
"# Publish the recording to meshcat.\n",
"meshcat_vis.publish_recording()\n",
"# Stop recording.\n",
"meshcat_vis.stop_recording()\n",
"\n",
"# Render meshcat's current state.\n",
"meshcat_vis.vis.render_static()"
Expand Down

0 comments on commit db3a546

Please sign in to comment.