FrankaHWSim
默认情况下,Gazebo ROS 只能仿真具有 “标准” 硬件接口的关节,如关节状态接口Joint State Interfaces和关节命令接口Joint Command Interfaces。然而,我们的机器人与这种架构完全不同!除了这些特定于关节的接口之外,它还支持 特定于机器人 的接口,如 FrankaModelInterface (参见 franka_hw)。自然 gazebo 默认不理解这些自定义硬件接口。这就是 FrankaHWSim 插件的作用。
为了让机器人能够支持 Franka 接口,只需在 URDF 中声明一个自定义的 robotsSimType:
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>${arm_id}</robotNamespace>
<controlPeriod>0.001</controlPeriod>
<robotSimType>franka_gazebo/FrankaHWSim</robotSimType>
</plugin>
<self_collide>true</self_collide>
</gazebo>当使用 模型生成器 生成此机器人时,此插件将加载到 gazebo 节点中。它将扫描 URDF 并尝试查找支持的硬件接口。目前只支持 franka_hw 提供的部分接口:
接口 | 功能 | |
|---|---|---|
✔ |
| 读取关节状态 |
✔ |
| 给关节级扭矩指令并读取关节状态。 |
✔ |
| 给关节速度指令并读取关节状态。 |
✔ |
| 给关节角度指令并读取关节状态。 |
✔ |
| 读取整个机器人状态 |
✔ |
| 读取机器人的动力学和运动学模型 |
✘ |
| 给笛卡尔位姿指令并读取整个机器人状态 |
✘ |
| 给笛卡尔速度指令并读取整个机器人状态 |
重要
这意味着只能仿真那些要求这些支持的接口的控制器,而不是其他的!例如,笛卡尔阻抗示例控制器可以被仿真,因为它只需要 EffortJoint-、FrankaState- 和 FrankaModelInterface。然而,关节阻抗示例控制器不能被仿真,因为它需要尚不支持的 FrankaPoseCartesianInterface。
除了实时硬件接口外,FrankaHWSim 插件支持 franka_control 支持的一些非实时命令:
服务 / 类型 | 解释 | |
|---|---|---|
✘ |
| Gazebo 不仿真内部阻抗控制器,而是直接设置扭矩命令 |
✘ |
| Gazebo 不仿真内部阻抗控制器,而是直接设置扭矩命令 |
✔ |
| 设置 |
✔ |
| 设置 |
✔ |
| 设置阈值,高于该阈值外部力旋量被视为接触和碰撞。 |
✘ |
| 尚未实现 |
✔ |
| 设置外部负载以补偿其重力,例如抓取的物体。还可以通过分别设置对应质量、惯性张量和负载质心的 ROS 参数 |
✔ |
| 这是一项仅在 |