如何在 MultibodyPlant 中设置特定实体的摩擦属性(或任何几何属性)?
How do I set the friction properties (or any GeometryProperties) of a specific body in MultibodyPlant?
我想知道如何在 MultibodyPlant
中设置物体的摩擦属性。
更具体地说,我有一个从 SDF 读入的模型实例,我想在该模型实例中添加或更改特定物体的摩擦属性。
设置摩擦特性的方法有多种。除了您非常具体的问题之外,我还将概述多个工作流程。 (作为旁注,虽然其中一些已记录在案,但不一定能在 doxygen 中发现 - 甚至呈现 - 这是一个悬而未决的问题,需要解决,因此存在问题)。
- 在urdf/sdf中定义。
- Drake 通过
<geometry>
标签提供与接触属性相关的自定义标签(包括摩擦等)。 URDF/SDF 中的标签相同,但使用方式略有不同(基于 SDF 与 URDF 的风格)。可以找到详细信息 here for sdf 和
here for urdf.
- 通过 API 添加新几何体并在定义中包含摩擦力。
- MultibodyPlant 有一个 API 用于将几何体分配给实体。有多种变体:
- Adding a geometry to a body and explicitly defining the friction
- 这是遗留糖 API。偏爱以
ProximityProperties
为首选的APIAPI.
- Generally defining ProximityProperties
- 在这种情况下,唯一的问题是,我的邻近属性从何而来?
#include "drake/geometry/proximity_properties.h"
#include "drake/multibody/plant/multibody_plant.h"
// Omitting drake:: namespaces for clarity.
MultibodyPlant<double> plant;
// Populate plant with bodies.
ProximityProperties contact_props;
AddContactMaterial({}, {}, CoulombFriction<double>(mu_s, mu_d), &contact_props);
// Assume we've defined body, X_BG, shape, and name elsewhere.
plant.RegisterCollisionGeometry(body, X_BG, shape, name, contact_props);
- Add/Update 到 urdf/sdf 中定义的几何
- 在这种情况下,我们需要根据它与物体的关联来更改
SceneGraph
中的几何定义。这意味着,从 Body
开始,我们需要得到 GeometryId
。我们将假设已经完成并且您拥有此工作流程的 GeometryId
。
SceneGraph<double> sg;
const GeometryId g_id = ...;
CoulombFriction<double> friction(mu_s, mu_d);
ProximityProperties new_props;
const ProximityProperties* curr_props =
sg.model_inspector().GetProximityProperties(g_id);
if (curr_props != nullptr) {
new_props = *curr_props;
}
// Replaces old friction definition, or adds it if previously absent.
new_props.UpdateProperty("material", "coulomb_friction", friction);
sg.AssignRole(g_id, new_props, RoleAssign::kReplace);
我想知道如何在 MultibodyPlant
中设置物体的摩擦属性。
更具体地说,我有一个从 SDF 读入的模型实例,我想在该模型实例中添加或更改特定物体的摩擦属性。
设置摩擦特性的方法有多种。除了您非常具体的问题之外,我还将概述多个工作流程。 (作为旁注,虽然其中一些已记录在案,但不一定能在 doxygen 中发现 - 甚至呈现 - 这是一个悬而未决的问题,需要解决,因此存在问题)。
- 在urdf/sdf中定义。
- Drake 通过
<geometry>
标签提供与接触属性相关的自定义标签(包括摩擦等)。 URDF/SDF 中的标签相同,但使用方式略有不同(基于 SDF 与 URDF 的风格)。可以找到详细信息 here for sdf 和 here for urdf.
- Drake 通过
- 通过 API 添加新几何体并在定义中包含摩擦力。
- MultibodyPlant 有一个 API 用于将几何体分配给实体。有多种变体:
- Adding a geometry to a body and explicitly defining the friction
- 这是遗留糖 API。偏爱以
ProximityProperties
为首选的APIAPI.
- 这是遗留糖 API。偏爱以
- Generally defining ProximityProperties
- 在这种情况下,唯一的问题是,我的邻近属性从何而来?
- Adding a geometry to a body and explicitly defining the friction
#include "drake/geometry/proximity_properties.h" #include "drake/multibody/plant/multibody_plant.h" // Omitting drake:: namespaces for clarity. MultibodyPlant<double> plant; // Populate plant with bodies. ProximityProperties contact_props; AddContactMaterial({}, {}, CoulombFriction<double>(mu_s, mu_d), &contact_props); // Assume we've defined body, X_BG, shape, and name elsewhere. plant.RegisterCollisionGeometry(body, X_BG, shape, name, contact_props);
- MultibodyPlant 有一个 API 用于将几何体分配给实体。有多种变体:
- Add/Update 到 urdf/sdf 中定义的几何
- 在这种情况下,我们需要根据它与物体的关联来更改
SceneGraph
中的几何定义。这意味着,从Body
开始,我们需要得到GeometryId
。我们将假设已经完成并且您拥有此工作流程的GeometryId
。
SceneGraph<double> sg; const GeometryId g_id = ...; CoulombFriction<double> friction(mu_s, mu_d); ProximityProperties new_props; const ProximityProperties* curr_props = sg.model_inspector().GetProximityProperties(g_id); if (curr_props != nullptr) { new_props = *curr_props; } // Replaces old friction definition, or adds it if previously absent. new_props.UpdateProperty("material", "coulomb_friction", friction); sg.AssignRole(g_id, new_props, RoleAssign::kReplace);
- 在这种情况下,我们需要根据它与物体的关联来更改