1

我正在使用以下代码创建 LQR 控制器:

systems::controllers::LinearQuadraticRegulator(
            plant, context, Q, R,
            Eigen::Matrix<double, 0, 0>::Zero() /* No cross state/control costs */,
            actuation_port_index); 
  • plant是类型的引用MultibodyPlant<double>
  • context是类型的引用Context<double>
  • Q是类型Eigen::Matrix<double, 6, 6>
  • R是类型Vector1d

用gdb调试显示错误来自multibody_plant.cc

MultibodyPlant<T>::CalcPointPairPenetrations

我不确定为什么它不使用MultibodyPlant<double>::CalcPointPairPenetrations

万一这很重要,我的plant对象是从sdf具有以下几行的文件中加载的

    auto pair = AddMultibodyPlantSceneGraph(&builder, std::make_unique<MultibodyPlant<double>>(FLAGS_time_step));

    MultibodyPlant<double>& plant = pair.plant;

    const std::string model_filename = getSrcDir() + "/../res/plant.sdf";
    Parser(&plant, &scene_graph).AddModelFromFile(model_filename);
4

2 回答 2

2

虽然我同意错误消息有点迟钝,但我怀疑问题是真实的......我敢打赌你正在建模一个具有接触动力学的系统(可能是偶然的)并且 LQR 不知道如何处理非光滑力学。

当您将 a 传递System<double>给 LQR 方法时,它会将其转换为ToAutoDiffXd(),然后评估动力学(以获得线性化)。这就是错误是关于MultibodyPlant<AutoDiffXd>(不是double)的原因。对于您的系统,动态需要调用碰撞引擎,它不是完全可微的(还),因此会抛出错误消息。

设置time_step=0从时间步进模型到连续时间模型的变化,并确实改变了与碰撞引擎的交互。因此,在某些情况下可能会有所帮助。

但我认为,解决方案是确定您是否只是偶然地(通过您的 SDF)包含碰撞元素——例如,您实际上并没有尝试实现物理。如果是,请尝试在您的 SDF 中将它们注释掉以解决此问题。也许我们可以/应该提供一些选项,让 LQR 更容易忽略这些选项。

更新:我已经打开了https://github.com/RobotLocomotion/drake/issues/11120以使其稍微好一点。

于 2019-04-01T10:44:53.947 回答
0

FLAGS_time_step当大于零时,我有相同的行为。

设置FLAGS_time_step0.0我解决了这个问题。

想了想,好像是个bug。

于 2019-04-01T07:14:51.343 回答