franka_control
ROS 节点 franka_control_node 和 franka_combined_control_node 是用于 ROS control 的硬件节点,它们使用 franka_hw 中的相应硬件类。他们提供了各种 ROS 服务,以在 ROS 生态系统中公开完整的 libfranka API。它提供以下服务:
franka_msgs::SetJointImpedance指定内部控制器的关节刚度(阻尼自动从刚度导出)。
franka_msgs::SetCartesianImpedance指定内部控制器的笛卡尔刚度(阻尼自动从刚度导出)。
franka_msgs::SetEEFrame指定从 <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::SetKFrame指定从 <arm_id>_K 到 <arm_id>_EE 坐标系的变换。
franka_msgs::SetForceTorqueCollisionBehavior为外部笛卡尔力旋量设置阈值以配置碰撞反射。
franka_msgs::SetFullCollisionBehavior在笛卡尔和关节层级上设置外力阈值以配置碰撞反射。
franka_msgs::SetLoad设置外部负载以进行补偿(例如一个抓取的物体)。
std_srvs::Trigger服务允许连接和断开硬件节点(从 0.8.0 开始可用)。当没有活动(命令)控制器在运行时,可以断开硬件节点,为非 fci 应用程序释放相应的机器人,例如基于 Desk 桌面的操作。一旦想恢复 fci 操作,可以调用 connect 并再次启动基于 ros_control 的控制器
重要
<arm_id>_EE 坐标系表示可配置的末端执行器坐标系的一部分,可以在运行时通过franka_ros进行调整。<arm_id>_K 坐标系标记内部笛卡尔阻抗的中心。它还可以作为外部力旋量的参考坐标系。<arm_id>_EE 和 <arm_id>_K 都不包含在 URDF 中,因为它们可以在运行时更改。 默认情况下,<arm_id> 设置为 “panda”。
末端执行器坐标系概览。
要在机器人处于反射模式时从错误和反射中恢复,可以使用 Franka_msgs::ErrorRecoveryAction。这可以通过 action 客户端或通过在 action 目标主题上发布来实现。
rostopic pub -1 /franka_control/error_recovery/goal franka_msgs/ErrorRecoveryActionGoal "{}"恢复后,franka_control_node 重新启动正在运行的控制器。这是可能的,因为当触发机器人反射或发生错误时,节点不会死亡。所有这些功能都由 franka_control_node 提供,其可以使用以下命令启动:
roslaunch franka_control franka_control.launch robot_ip:=<fci-ip> # mandatory load_gripper:=<true|false> # default: true robot:=<panda|fr3> # default: panda
除了加载 franka_control_node 之外,launch 文件还会启动 franka_control::FrankaStateController 来读取和发布机器人状态,包括外部力旋量、可配置的变换和使用 rivz 进行可视化所需的关节状态。出于可视化目的,一个 robot_state_publisher 节点已启动。
这个包还实现了 franka_combined_control_node,一个基于 franka_hw::FrankaCombinedHW 类的 ros_control 的硬件节点。加载的机器人组是通过 ROS 参数服务器配置的。这些参数必须在硬件节点的命名空间中(参见 franka_combined_control_node.yaml 作为参考),如下所示:
robot_hardware: - panda_1 - panda_2 # (...) panda_1: type: franka_hw/FrankaCombinableHW arm_id: panda_1 joint_names: - panda_1_joint1 - panda_1_joint2 - panda_1_joint3 - panda_1_joint4 - panda_1_joint5 - panda_1_joint6 - panda_1_joint7 # Configure the threshold angle for printing joint limit warnings. joint_limit_warning_threshold: 0.1 # [rad] # Activate rate limiter? [true|false] rate_limiting: true # Cutoff frequency of the low-pass filter. Set to >= 1000 to deactivate. cutoff_frequency: 1000 # Internal controller for motion generators [joint_impedance|cartesian_impedance] internal_controller: joint_impedance # Configure the initial defaults for the collision behavior reflexes. collision_config: lower_torque_thresholds_acceleration: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm] upper_torque_thresholds_acceleration: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm] lower_torque_thresholds_nominal: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm] upper_torque_thresholds_nominal: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm] lower_force_thresholds_acceleration: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm] upper_force_thresholds_acceleration: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm] lower_force_thresholds_nominal: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm] upper_force_thresholds_nominal: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm] panda_2: type: franka_hw/FrankaCombinableHW arm_id: panda_2 joint_names: - panda_2_joint1 - panda_2_joint2 - panda_2_joint3 - panda_2_joint4 - panda_2_joint5 - panda_2_joint6 - panda_2_joint7 # Configure the threshold angle for printing joint limit warnings. joint_limit_warning_threshold: 0.1 # [rad] # Activate rate limiter? [true|false] rate_limiting: true # Cutoff frequency of the low-pass filter. Set to >= 1000 to deactivate. cutoff_frequency: 1000 # Internal controller for motion generators [joint_impedance|cartesian_impedance] internal_controller: joint_impedance # Configure the initial defaults for the collision behavior reflexes. collision_config: lower_torque_thresholds_acceleration: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm] upper_torque_thresholds_acceleration: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm] lower_torque_thresholds_nominal: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm] upper_torque_thresholds_nominal: [20.0, 20.0, 18.0, 18.0, 16.0, 14.0, 12.0] # [Nm] lower_force_thresholds_acceleration: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm] upper_force_thresholds_acceleration: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm] lower_force_thresholds_nominal: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm] upper_force_thresholds_nominal: [20.0, 20.0, 20.0, 25.0, 25.0, 25.0] # [N, N, N, Nm, Nm, Nm] # (+ more robots ...)
备注
请务必选择唯一且一致的 arm_id 参数。 ID 必须与关节名称中的前缀匹配,并且应该根据加载到控制节点命名空间的机器人描述。
关于基于参数加载硬件类的更多信息,请参考 https://github.com/ros-controls/ros_control 中 combined_robot_hw::CombinedRobotHW 的官方文档。
第二个重要的参数文件(参见 franka_ros/franka_control/config/default_combined_controllers.yaml作为参考)配置了一组默认控制器,可以通过硬件节点启动。控制器必须与启动的硬件相匹配。提供的默认参数化(此处为 2 个机器人)如下所示:
panda_1_state_controller: type: franka_control/FrankaStateController arm_id: panda_1 joint_names: - panda_1_joint1 - panda_1_joint2 - panda_1_joint3 - panda_1_joint4 - panda_1_joint5 - panda_1_joint6 - panda_1_joint7 publish_rate: 30 # [Hz] panda_2_state_controller: type: franka_control/FrankaStateController arm_id: panda_2 joint_names: - panda_2_joint1 - panda_2_joint2 - panda_2_joint3 - panda_2_joint4 - panda_2_joint5 - panda_2_joint6 - panda_2_joint7 publish_rate: 30 # [Hz] # (+ more controllers ...)
我们提供了一个 launch 启动文件来运行 franka_combined_control_node,其中包含用户指定的硬件和控制器配置文件,默认配置为 2 个机器人。用以下命令启动它:
roslaunch franka_control franka_combined_control.launch robot_ips:=<your_robot_ips_as_a_map> # mandatory robot:=<path_to_your_robot_description> args:=<xacro_args_passed_to_the_robot_description> # if needed robot_id:=<name_of_your_multi_robot_setup> hw_config_file:=<path_to_your_hw_config_file> # includes the robot ips! controllers_file:=<path_to_your_default_controller_parameterization> controllers_to_start:=<list_of_default_controllers_to_start> joint_states_source_list:=<list_of_sources_to_fuse_a_complete_joint_states_topic>
这个 launch 启动文件可以被参数化以运行任意数量的机器人。为此,只需以 franka_control/config/franka_combined_control_node.yaml 和 franka_ros/franka_control/config/default_combined_controllers.yaml 的样式编写自己的配置文件。
重要
请务必将机器人的正确 IP 作为映射传递给franka_combined_control.launch。这看起来像:{<arm_id_1>/robot_ip: <my_ip_1>, <arm_id_2>/robot_ip: <my_ip_2>, …}