有多少人工,就有多少智能

Franka - Robot - Ros - FrankaHWSim

默认情况下, Gazebo ROS只能使用“标准”硬件接口(如关节状态接口和关节命令接口)模拟关节。 然而, 我们的机器人与这种架构完全不同! 除了特定于关节的接口, 它还支持Franak机器人特定的接口, 如FrankaModelInterface。 当然, 默认情况下, Gazebo无法理解这些自定义硬件接口。 这既是插件的用武之地。

要使您的机器人能够支持Franka接口, 只需在URDF中声明一个自定义:robotSimtype

<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。

除了实时硬件接口之外,该插件还支持一些非实时命令 franka_control支持:

 

FrankaGripperSim

此插件模拟 Gazebo 中的franka_gripper_node。这是作为 ROS 控制器完成的,用于 两个手指关节带有位置和力控制器。它提供与真实抓手节点相同的五个操作:

  • /<arm_id>/franka_gripper/homing

  • /<arm_id>/franka_gripper/stop

  • /<arm_id>/franka_gripper/move

  • /<arm_id>/franka_gripper/grasp

  • /<arm_id>/franka_gripper/gripper_action

该操作有一个错误,如果设置目标宽度,它将不会成功也不会中止让手指张开。这是因为缺少关节限制接口,该接口让手指在其极限摆动。现在只使用grasp动作来闭合手指!

假设URDF包含两个可以进行力控的手指关节,即声明了相应的传输。此控制器在其命名空间中需要以下参数:

  • type(string, required): 应该是franka_gazebo/FrankaGripperSim。

  • arm_id(字符串,必填):熊猫的手臂ID,用于推断手指关节的名称。

  • finger1/gains/p(double,必填):第一根手指的位置力控制器的比例增益。

  • finger1/gains/i(double,默认值:0):第一根手指的位置力控制器的积分增益。

  • finger1/gains/d(double,默认值:0):第一根手指的位置力控制器的差分增益。

  • finger2/gains/p(double,必填):第二根手指的位置力控制器的比例增益。

  • finger2/gains/i(double,默认值:0):第二根手指的位置力控制器的积分增益。

  • finger2/gains/d(double,默认值:0):第二根手指的位置力控制器的差分增益。

  • move/width_tolerance(double,默认):这个参数决定了机器人在移动过程中允许的宽度误差,确保机器人能够在预定轨迹或路径上准确地进行运动

  • grasp/resting_threshold(double,默认):参数决定了抓手在完成抓取动作后,达到稳定状态所需的条件,例如力、位置或速度的变化范围

  • grasp/consecutive_samples(double,默认值:3):指定抓取动作中连续采样的数量。这个参数可能决定了机器人在执行抓取任务时需要连续采集多少次传感器数据或图像数据,以确保抓取动作的稳定性和准确性

  • gripper_action/width_tolerance(double,默认5𝑚𝑚):通常用于指定抓手在抓取动作中宽度的公差范围,即抓手在抓取物体时应如何精确地调整其指尖的位置

  • gripper_action/speed(double,默认):夹持器动作期间使用的速度。

JointStateInterface

要能够从ROS控制器访问关节状态接口,你只需在URDF中的任意传动标签中声明相应的关节。然后关节状态接口将自动可用。通常你会为诸如EffortJointInterface之类的命令接口声明传动标签。

注意: 对于任何以整数 N 命名的关节,FrankaHWSim 将自动补偿其重力,以模拟 libfranka 的行为。命名格式为 <arm_id>_jointN

EffortJointInterface

要能够从控制器向关节发送力命令,只需在URDF中为该关节声明一个传动标签,并指定相应的硬件接口类型:

<transmission name="${joint}_transmission">
 <type>transmission_interface/SimpleTransmission</type>
 <joint name="${joint}">
   <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
 </joint>
 <actuator name="${joint}_motor">
   <hardwareInterface>${transmission}</hardwareInterface>
 </actuator>
</transmission>

<gazebo reference="${joint}">
  <!-- Needed for ODE to output external wrenches on joints -->
  <provideFeedback>true</provideFeedback>
</gazebo>

注: 如果你希望能够读取来自外部的力或扭矩(例如碰撞),请确保将标签设置为 <provideFeedback>true

FrankaStateInterface

这是一个特定于机器人的接口,因此与普通硬件接口有些不同。要能够从控制器访问 franka 状态接口,请在你的 URDF 中为所有七个关节声明以下传动标签:

<transmission name="${arm_id}_franka_state">
  <type>franka_hw/FrankaStateInterface</type>
  <joint name="${arm_id}_joint1"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
  <joint name="${arm_id}_joint2"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
  <joint name="${arm_id}_joint3"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
  <joint name="${arm_id}_joint4"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
  <joint name="${arm_id}_joint5"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
  <joint name="${arm_id}_joint6"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
  <joint name="${arm_id}_joint7"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>

  <actuator name="${arm_id}_motor1"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
  <actuator name="${arm_id}_motor2"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
  <actuator name="${arm_id}_motor3"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
  <actuator name="${arm_id}_motor4"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
  <actuator name="${arm_id}_motor5"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
  <actuator name="${arm_id}_motor6"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
  <actuator name="${arm_id}_motor7"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
</transmission>

 

当你的控制器通过 FrankaStateInterface 访问机器人状态时,可以预期以下值会被模拟:

 

 

 

FrankaModelInterface

这是一个特定于机器人的接口,因此与普通硬件接口有些不同。要能够从控制器访问 franka 模型接口,请在你的 URDF 中为运动链的根部(例如 panda_joint1)和末端(例如 panda_joint8)声明以下传动标签:

<transmission name="${arm_id}_franka_model">
  <type>franka_hw/FrankaModelInterface</type>
  <joint name="${root}">
    <role>root</role>
    <hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface>
  </joint>
  <joint name="${tip}">
    <role>tip</role>
    <hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface>
  </joint>

  <actuator name="${root}_motor_root"><hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface></actuator>
  <actuator name="${tip}_motor_tip"  ><hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface></actuator>
</transmission>

 

模型函数本身是用 KDL 实现的。它从 URDF 中获取运动学结构和惯性属性,以计算模型属性,如雅可比矩阵或质量矩阵。

摩擦(Friction)

为了使物体之间(如手指与物体)具有适当的摩擦力,你需要在URDF中调整一些Gazebo参数。对于link,我们建议设置以下参数:

  • panda_finger_joint1
  • panda_finger_joint2

通常,你可以在URDF中的 <gazebo> 标签内添加以下参数来调整摩擦:

<gazebo>
  <friction>摩擦系数</friction>
</gazebo>
<gazebo reference="${link}">
  <collision>
    <max_contacts>10</max_contacts>
    <surface>
      <contact>
        <ode>
          <!-- These two parameter need application specific tuning. -->
          <!-- Usually you want no "snap out" velocity and a generous -->
          <!-- penetration depth to keep the grasping stable -->
          <max_vel>0</max_vel>
          <min_depth>0.003</min_depth>
        </ode>
      </contact>
      <friction>
        <ode>
          <!-- Rubber/Rubber contact -->
          <mu>1.16</mu>
          <mu2>1.16</mu2>
        </ode>
      </friction>
      <bounce/>
    </surface>
  </collision>
</gazebo>

franka_msgs

此软件包包含主要用于相关软件包的消息、服务和动作类型,用于发布机器人状态或在ROS生态系统中公开libfranka API。有关此软件包提供的服务和动作的更多信息,请参阅 franka_control.franka_hwfranka_control

panda_moveit_config

This package was moved to the ros_planning repos.

有关更多详细信息、文档和教程,请查看 MoveIt! 教程网站。

Writing your own controller

来自示例控制器包的所有示例控制器都派生自 controller_interface::MultiInterfaceController 类,该类允许在一个控制器实例中声明多达四个接口。你的类声明看起来如下:

class NameOfYourControllerClass : controller_interface::MultiInterfaceController <
                              my_mandatory_first_interface,
                              my_possible_second_interface,
                              my_possible_third_interface,
                              my_possible_fourth_interface> {
  bool init (hardware_interface::RobotHW* hw, ros::NodeHandle& nh);  // mandatory
  void update (const ros::Time& time, const ros::Duration& period);  // mandatory
  void starting (const ros::Time& time)   // optional
  void stopping (const ros::Time& time);  // optional
  ...
}

可用的接口在 franka_hw 部分中进行了描述。

请注意,可声明的命令接口组合是有限制的,因为同时命令关节位置和笛卡尔位姿等情况是没有意义的。像 JointStateInterfaceFrankaStateInterfaceFrankaModelInterface 这样的只读接口可以始终被声明,并且不受限制。

可以声明的命令接口包括:

 

提供 EffortJointInterface 与运动生成器接口相结合的想法是向用户暴露内部运动生成器。与运动生成器命令对应的计算期望关节位姿在机器人状态中将在一个时间步后可用。此组合的一个用例是使用自己的关节级扭矩控制器跟随笛卡尔轨迹。在这种情况下,你将声明 EffortJointInterface + FrankaCartesianPoseInterface 的组合,将你的轨迹输入到 FrankaCartesianPoseInterface 中,并根据来自机器人状态的期望关节位姿 (q_d) 计算关节级扭矩命令。这使得可以使用机器人的内置逆运动学,而不必自己解决。

要实现一个完全功能的控制器,你必须实现至少继承的虚拟函数 initupdate。初始化(例如起始位姿)应在 starting 函数中进行,该函数在重新启动控制器时被调用,而 init 函数仅在加载控制器时调用。stopping 方法应包含与关机相关的功能(如需要)。

在关闭控制器之前,始终命令一个温和的减速。当使用速度接口时,不要在 stopping 函数中简单地命令零速度,因为这可能在机器人仍在移动时被调用,这相当于命令一个瞬间的速度跳跃,从而导致非常高的关节级扭矩。在这种情况下,保持相同的速度并停止控制器会比发送零速度更好,让机器人自行处理减速。

你的控制器类必须正确导出,使用 pluginlib 来实现这一点,这需要添加以下内容:

#include <pluginlib/class_list_macros.h>
// Implementation ..
PLUGINLIB_EXPORT_CLASS(name_of_your_controller_package::NameOfYourControllerClass,
                       controller_interface::ControllerBase)

在文件末尾添加上述代码后,你还需要定义一个 .xml 文件,内容如下:

<library path="lib/lib<name_of_your_controller_library>">
  <class name="name_of_your_controller_package/NameOfYourControllerClass"
         type="name_of_your_controller_package::NameOfYourControllerClass"
         base_class_type="controller_interface::ControllerBase">
    <description>
      Some text to describe what your controller is doing
    </description>
  </class>
</library>
 

要导出该文件,你需要添加以下内容:

<export>
  <controller_interface plugin="${prefix}/plugin.xml"/>
</export>

要将控制器名称及其类型加载到 ROS 参数服务器中,你需要在 package.xml 中添加至少一个控制器名称和控制器类型。此外,你可以包含其他需要的参数。示例 configuration.yaml 文件可能如下所示:

your_custom_controller_name:
  type: name_of_your_controller_package/NameOfYourControllerClass
  additional_example_parameter: 0.0
  # ..

现在你可以使用 ROS 控制中的节点或通过 franka_control_node 提供的服务调用来启动你的控制器。只需确保 controller_spawnerhardware_manager 运行在同一命名空间中。有关更多详细信息,请查看 franka_example_controllers 包中的控制器或 ROS 控制教程。

 

posted @ 2024-07-25 22:46  lvdongjie-avatarx  阅读(40)  评论(0编辑  收藏  举报