输入端口的索引是什么意思?

What's the meaning of the index of the input port?

在MIT6.832 HW2"Cart-Pole: Linearization and LQR Balncing"中,carpole定义为:

# instantiate the cart-pole and the scene graph
cartpole, scene_graph = AddMultibodyPlantSceneGraph(builder, time_step=0.0)
urdf_path = FindResource('models/undamped_cartpole.urdf')
Parser(cartpole).AddModelFromFile(urdf_path)
cartpole.Finalize()

稍后carpole的驱动输入端口设置为0:

# fix the input port to zero and get its index for the lqr function
cartpole.get_actuation_input_port().FixValue(context, [0])
input_i = cartpole.get_actuation_input_port().get_index() # input_i = 3

但是,输入端口的索引是 3,而不是 0,这让我很困惑。


这里还有一个额外的相关问题是,在定义一个新系统(比如继承自 VectorSystem)时,我们可以在哪里定义输入和输出端口?

我看了一段时间HW1的cartpole模型,发现端口使用比较混乱。有时它使用 get_xxx_port(),而其他情况下它使用 get_xxx_port(0),并在括号内包含特定的端口号。

这是一个非常合理的问题。

drake 中的系统可以有多个输入端口(或没有输入端口)。通常,可以使用 get_input_port(index) 方法访问它们。但是,如果您正在构建一个具有多个输入的更复杂的系统,例如 MultibodyPlant,那么您不希望必须通过一些索引来区分不同的输入端口,而是通过名称。如此多的系统为自己添加了额外的方法,从而提供了访问同一端口的额外方法。例如。 MultibodyPlant 优惠(相当于 c++)

def get_actuation_input_port():
  return get_input_port(3)

因此没有人必须记住扭矩进入端口 3。但是您可以使用任一方法获得对端口的引用。

与端口索引分开,我们需要能够在给定上下文的情况下评估系统的输入端口。当端口在图中是"wired up"到另一个系统时,那么像u = cartpole.get_actuation_input_port().Eval(context)这样的调用将调用另一个系统的输出方法。但能够将输入设置为常量值也很有用,因此我们也提供了该接口。这就是你上面的代码片段中发生的事情:

cartpole.get_actuation_input_port().FixValue(context, [0])

此行将上下文中输入端口的值设置为向量——此处恰好是大小为 1 的向量,唯一的元素为零。对于具有四个执行器的机器人,它可能是

my_robot.get_actuation_input_port().FixValue(context, [0, 0, 0, 0])