I have the code above and snipped actuators part of urdf as below. I am facing
RuntimeError: Actuation input port for model instance digit must be connected.
even after passing diagram to the simulator.
I tried another answer from Dr. Tedrake that passing plant instead of diagram to simulator might be the issue, but I am passing the correct thing to the simulator and still facing the same error.
def run_pid_control():
builder = DiagramBuilder()
plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 1e-3)
parser = Parser(plant)
ConfigureParser(parser)
parser.AddModelFromFile(
# "/work/digit_fixed.urdf"
"/work/digit_for_drake.urdf"
# "package://underactuated/models/atlas/atlas.urdf"
)
parser.AddModelsFromUrl(
"package://underactuated/models/littledog/ground.urdf"
)
plant.Finalize()
print(plant.num_positions())
print(plant.num_joints())
print(plant.GetPositionNames())
print(plant.GetStateNames())
print(len(plant.GetStateNames()))
print("act")
print(plant.num_actuators())
print(plant.num_frames())
visualizer = MeshcatVisualizer.AddToBuilder(builder, scene_graph, meshcat)
diagram = builder.Build()
simulator = Simulator(diagram)
context = simulator.get_mutable_context()
plant_context = plant.GetMyContextFromRoot(context)
set_home(plant, plant_context)
# x0 = S @ plant.get_state_output_port().Eval(plant_context)
# control.get_input_port_desired_state().FixValue(
# control.GetMyContextFromRoot(context), x0
# )
simulator.set_target_realtime_rate(1.0 if running_as_notebook else 0)
visualizer.StartRecording()
print(plant.GetPositionsAndVelocities(plant_context))
print(len(plant.GetPositionsAndVelocities(plant_context)))
simulator.AdvanceTo(0.5)
visualizer.PublishRecording()
run_pid_control()
<joint name="shoulder_yaw_joint_right" type="revolute">
<origin rpy="-1.57079632679 0 0" xyz="0 0.165 -0.1"/>
<axis xyz="0 0 1"/>
<parent link="right_shoulder_pitch"/>
<child link="right_shoulder_yaw"/>
<limit effort="1.4" lower="-1.7453" upper="1.7453" velocity="10"/>
</joint>
<joint name="elbow_joint_right" type="revolute">
<origin rpy="-1.57079632679 -0.3926991 0" xyz="0 0.0385 0.185"/>
<axis xyz="0 0 1"/>
<parent link="right_shoulder_yaw"/>
<child link="right_elbow"/>
<limit effort="1.4" lower="-1.3526" upper="1.3526" velocity="12.5"/>
</joint>
<transmission type="SimpleTransmission">
<joint name="hip_abduction_left"/>
<actuator name="hip_abduction_left"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="hip_rotation_left"/>
<actuator name="hip_rotation_left"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="hip_flexion_left"/>
<actuator name="hip_flexion_left"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="knee_joint_left"/>
<actuator name="knee_joint_left"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="shin_to_tarsus_left"/>
<actuator name="shin_to_tarsus_left"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="toe_pitch_joint_left"/>
<actuator name="toe_pitch_joint_left"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="toe_roll_joint_left"/>
<actuator name="toe_roll_joint_left"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="shoulder_roll_joint_left"/>
<actuator name="shoulder_roll_joint_left"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="shoulder_pitch_joint_left"/>
<actuator name="shoulder_pitch_joint_left"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="shoulder_yaw_joint_left"/>
<actuator name="shoulder_yaw_joint_left"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="elbow_joint_left"/>
<actuator name="elbow_joint_left"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="hip_abduction_right"/>
<actuator name="hip_abduction_right"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="hip_rotation_right"/>
<actuator name="hip_rotation_right"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="hip_flexion_right"/>
<actuator name="hip_flexion_right"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="knee_joint_right"/>
<actuator name="knee_joint_right"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="shin_to_tarsus_right"/>
<actuator name="shin_to_tarsus_right"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="toe_pitch_joint_right"/>
<actuator name="toe_pitch_joint_right"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="toe_roll_joint_right"/>
<actuator name="toe_roll_joint_right"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="shoulder_roll_joint_right"/>
<actuator name="shoulder_roll_joint_right"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="shoulder_pitch_joint_right"/>
<actuator name="shoulder_pitch_joint_right"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="shoulder_yaw_joint_right"/>
<actuator name="shoulder_yaw_joint_right"/>
</transmission>
<transmission type="SimpleTransmission">
<joint name="elbow_joint_right"/>
<actuator name="elbow_joint_right"/>
</transmission>
</robot>
```
I tried another answer from Dr. Tedrake that passing plant instead of diagram to simulator might be the issue, but I am passing the correct thing to the simulator and still facing the same error.
The error message is pointing you at the solution. Your robot model has actuators (created via the transmission tags), which means your MultibodyPlant
has input ports associated with the torques for those actuators. You cannot simulate it without specifying some value for those inputs.
Adding
torques = builder.AddSystem(ConstantVectorSource(np.zeros(plant.num_actuators()))
builder.Connect(torques.get_output_port(), plant.get_actuation_input_port())
before building the diagram is perhaps the simplest way to get it working. Moving on from that, based on the PID controller that you might have started from, you add back the PID controller to provide values to that input port.