franka_bringup

备注

franka_ros2 不支持 Windows。

franka_ros2 仓库 包含 libfranka 的 ROS 2 集成。

小心

franka_ros2 正在快速开发中,可能出现破坏性变更。如有问题,请在 GitHub 报告。

安装

请参考 README.md

包概览

该包包含示例的启动文件以及基本的 franka.launch.py 启动文件,可用于在没有任何控制器的情况下启动机器人。

当你启动机器人时:

ros2 launch franka_bringup franka.launch.py arm_id:=fr3 robot_ip:=<fci-ip> use_rviz:=true

除了 joint_state_broadcaster 外,没有其他控制器在运行。但仍然可以与机器人建立连接,并在 RViz 中可视化当前机器人位姿。在此模式下,当用户按下停止按钮时可以引导机器人。然而,一旦启动使用 effort_command_interface 的控制器,机器人将使用 libfranka 的力矩接口。例如,可以通过运行以下命令启动 gravity_compensation_example_controller:

ros2 control load_controller --set-state active  gravity_compensation_example_controller

这相当于运行 Gravity Compensation 中提到的 gravity_compensation_example_controller 示例。

当控制器停止时:

ros2 control set_controller_state gravity_compensation_example_controller inactive

机器人将停止力矩控制,仅通过 FCI 发送其当前状态。

现在你可以选择再次启动相同的控制器:

ros2 control set_controller_state gravity_compensation_example_controller active

或者加载并启动不同的控制器:

ros2 control load_controller --set-state active joint_impedance_example_controller

启用命名空间的启动文件

为了演示如何在指定命名空间内启动机器人,我们提供了位于 franka_bringup/launch/example.launch.py 的示例启动文件。

默认情况下,example.launch.py 配置为从位于 franka_bringup/launch/ 目录的 YAML 文件 franka.ns-config.yaml 中读取机器人基本配置。你也可以通过命令行指定路径来使用不同的 YAML 文件。

franka.ns-config.yaml 文件指定关键参数,包括:

  • 机器人的 URDF 文件路径。

  • 机器人实例使用的命名空间。

  • 机器人实例的其他特定配置细节。

example.launch.py “包含” franka.ns-launch.py,该文件定义了机器人操作所需的核心节点。

franka.ns-launch.py 文件依赖于 ns-controllers.yaml 来配置 ros2_controller 框架。该配置确保控制器以与命名空间无关的方式加载,支持跨多个命名空间的一致行为。

ns-controllers.yaml 文件设计为可容纳零个或多个命名空间,前提是所有命名空间共享相同的节点配置参数。

每个配置和启动文件(franka.ns-config.yaml、example.launch.py、franka.ns-launch.py 和 ns-controllers.yaml)都包含详细的内联文档,指导用户理解其结构和使用方法。有关 ROS 2 中命名空间的更多信息,请参考 ROS 2 文档

要执行 ns-controllers.yaml 中定义的任意示例控制器,可以使用 example.launch.py 启动文件,并通过命令行参数指定所需的控制器名称。

首先 - 根据你的设置修改 franka.ns-config.yaml

然后,例如,要运行 move_to_start_example_controller,使用以下命令:

ros2 launch franka_bringup example.launch.py controller_name:=move_to_start_example_controller

非实时机器人参数设置

非实时机器人参数设置可以通过 ROS 2 服务完成。这些服务在机器人硬件初始化后被发布。

服务名称如下:

* /service_server/set_cartesian_stiffness
* /service_server/set_force_torque_collision_behavior
* /service_server/set_full_collision_behavior
* /service_server/set_joint_stiffness
* /service_server/set_load
* /service_server/set_parameters
* /service_server/set_parameters_atomically
* /service_server/set_stiffness_frame
* /service_server/set_tcp_frame

服务消息说明如下。

  • franka_msgs::srv::SetJointStiffness 指定内部控制器的关节刚度(阻尼由刚度自动导出)。

  • franka_msgs::srv::SetCartesianStiffness 指定内部控制器的笛卡尔刚度(阻尼由刚度自动导出)。

  • franka_msgs::srv::SetTCPFrame 指定从 <arm_id>_EE(末端执行器)到 <arm_id>_NE(名义末端执行器)坐标系的变换。从法兰到末端执行器坐标系的变换分为两个部分:<arm_id>_EE 到 <arm_id>_NE 坐标系,以及 <arm_id>_NE 到 <arm_id>_link8 坐标系。<arm_id>_NE 到 <arm_id>_link8 坐标系的变换只能通过管理员接口设置。

  • franka_msgs::srv::SetStiffnessFrame 指定从 <arm_id>_K 到 <arm_id>_EE 坐标系的变换。

  • franka_msgs::srv::SetForceTorqueCollisionBehavior 设置外部笛卡尔力旋量的阈值,以配置碰撞反应。

  • franka_msgs::srv::SetFullCollisionBehavior 设置笛卡尔空间和关节层面的外部力阈值,以配置碰撞反应。

  • franka_msgs::srv::SetLoad 设置外部负载以进行补偿(例如抓取物体的重量)。

启动 franka_bringup/franka.launch.py 文件以初始化机器人硬件:

ros2 launch franka_bringup franka.launch.py robot_ip:=<fci-ip>

下面是一个最小示例:

ros2 service call /service_server/set_joint_stif
fness franka_msgs/srv/SetJointStiffness "{joint_stiffness: [1000.0, 1000.0, 10
00.0, 1000.0, 1000.0, 1000.0, 1000.0]}"

重要

非实时参数设置仅可在机器人硬件处于 idle 模式时进行。如果控制器处于活动状态并占用命令接口,机器人将进入 move 模式。在 move 模式下无法进行非实时参数设置。

重要

<arm_id>_EE 坐标系表示可配置末端执行器坐标系的一部分,可以在运行时通过 franka_ros 进行调整。<arm_id>_K 坐标系表示内部笛卡尔阻抗的中心,也作为外部力旋量的参考坐标系。<arm_id>_EE 和 <arm_id>_K 都不包含在 URDF 中,因为它们可以在运行时更改。默认情况下,<arm_id> 设置为 “panda”。

../../../_images/frames1.svg

末端执行器坐标系概览。

非实时 ROS 2 操作

非实时 ROS 2 操作可以通过 ActionServer 执行。提供以下操作:

  • /action_server/error_recovery - 自动从机器人错误中恢复。

使用的消息如下:

  • franka_msgs::action::ErrorRecovery - 无参数。

示例用法::

ros2 action send_goal /action_server/error_recovery franka_msgs/action/ErrorRecovery {}

已知问题

  • 当在 MoveIt 中使用 fake_hardware 时,需要一些时间才能应用默认位置。