非实时机器人参数设置

非实时机器人参数设置可以通过 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, 1000.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

末端执行器坐标系概览。