0

I am using pydrake to learn the underactuated robotics. I am confused that how could I change the CompassGaitParams? For example, I want to change the leg length to 1.5,what should I do? I changed the example, but it failed this is the code:

import numpy as np
import matplotlib.pyplot as plt
from IPython import get_ipython
from underactuated.jupyter import AdvanceToAndVisualize, SetupMatplotlibBackend
plt_is_interactive = SetupMatplotlibBackend()
from pydrake.all import (ConstantVectorSource, DiagramBuilder,
                         PlanarSceneGraphVisualizer, SceneGraph, SignalLogger,
                         Simulator)
from pydrake.examples.compass_gait import (CompassGait, CompassGaitGeometry,CompassGaitParams)
builder = DiagramBuilder()
compass_gait = builder.AddSystem(CompassGait())
hip_torque = builder.AddSystem(ConstantVectorSource([0.0]))
builder.Connect(hip_torque.get_output_port(0), compass_gait.get_input_port(0))
compassgaitparams=CompassGaitParams()
compassgaitparams.set_length_leg(1.5)
scene_graph = builder.AddSystem(SceneGraph())
CompassGaitGeometry.AddToBuilder(
    builder, compass_gait.get_floating_base_state_output_port(),compassgaitparams,scene_graph)
visualizer = builder.AddSystem(
    PlanarSceneGraphVisualizer(scene_graph, xlim=[-1., 8.], ylim=[-1., 2.], 
                               show=plt_is_interactive))
builder.Connect(scene_graph.get_pose_bundle_output_port(),
                visualizer.get_input_port(0))
logger = builder.AddSystem(SignalLogger(14))
builder.Connect(compass_gait.get_output_port(1), logger.get_input_port(0))
diagram = builder.Build()
simulator = Simulator(diagram)
context = simulator.get_mutable_context()
context.SetAccuracy(1e-4)
context.SetContinuousState([0., 0., 0.4, -2.])
duration = 5.0 if get_ipython() else 0.1 # sets a shorter duration during testing
AdvanceToAndVisualize(simulator, visualizer, duration)

And the result is just like this: result

Axebobby
  • 31
  • 4

1 Answers1

1

It looks like you set the CompassGaitParams in the visualization routine (via CompassGaitGeometry) but did not update the parameters for the plant. To do that, you would need to do

params_in_context = compass_gait.GetMyMutableContextFromRoot(context).get_mutable_numeric_parameter(0) 
params_in_context.SetFrom(compassgaitparams)
Russ Tedrake
  • 4,703
  • 1
  • 7
  • 10