在 ROS1 (franka_ros) 中实现实时关节速度控制的标准方法是使用ros_control框架下的velocity_controllers/JointGroupVelocityController。它允许你直接向一个 topic 持续不断地发布速度数组底层硬件接口 (franka_hw) 会以 1kHz 的频率将这些速度指令下发给机械臂。以下是完整的配置和代码实现步骤1. 配置控制器 (YAML)你需要告诉 ROS 加载一个关节组速度控制器。在你的工作空间中或者直接在franka_control/config/default_controllers.yaml中添加以下配置joint_group_velocity_controller: type: velocity_controllers/JointGroupVelocityController joints: - panda_joint1 - panda_joint2 - panda_joint3 - panda_joint4 - panda_joint5 - panda_joint6 - panda_joint72. 启动系统与控制器注意不能同时运行位置控制器比如position_joint_trajectory_controller和速度控制器。在启动速度控制器前必须确保位置控制器没有在占用硬件接口。解锁 FCI在 Franka Desk (Web UI) 中确保外围控制 (FCI) 处于激活状态。启动底层节点roslaunch franka_control franka_control.launch robot_ip:your_robot_ip加载并启动速度控制器rosrun controller_manager spawner joint_group_velocity_controller如果之前有其他的控制器正在运行可以使用rqt_controller_manager图形界面或者命令行将旧的控制器 stop 掉然后再 startjoint_group_velocity_controller。3. 编写 Python 实时发布节点一旦joint_group_velocity_controller成功运行它会暴露一个名为/joint_group_velocity_controller/command的 topic。你需要向这个 topic 发布std_msgs/Float64MultiArray类型的消息。这是一个安全的测试代码框架。为了安全我将前 6 个关节设为 0仅让第 7 轴末端法兰以极其微小的速度 (0.05 rad/s) 旋转#!/usr/bin/env python # -*- coding: utf-8 -*- import rospy from std_msgs.msg import Float64MultiArray # 将 publisher 声明为全局变量以便在 shutdown_hook 中调用 pub None def shutdown_hook(): 当节点接收到关闭信号 (如 CtrlC) 时ROS 会保证在切断网络连接前执行此函数。 rospy.logwarn(收到退出信号触发安全停车机制正在发送全零速度...) if pub is not None: stop_cmd Float64MultiArray() stop_cmd.data [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] # 连续发送多次确保指令冲破网络缓冲到达控制器 for _ in range(5): pub.publish(stop_cmd) rospy.sleep(0.02) # 极短的延时 rospy.logwarn(刹车指令发送完毕节点安全关闭。) def velocity_control_node(): global pub rospy.init_node(franka_velocity_publisher_node, anonymousTrue) # 注册 ROS 的安全关闭回调 rospy.on_shutdown(shutdown_hook) pub rospy.Publisher(/joint_group_velocity_controller/command, Float64MultiArray, queue_size1) rate rospy.Rate(100) vel_cmd Float64MultiArray() rospy.loginfo(开始发布关节速度指令... 请随时准备按下急停) while not rospy.is_shutdown(): # 给第 7 轴一个微小的测试速度 (0.05 rad/s) vel_cmd.data [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.05] pub.publish(vel_cmd) rate.sleep() if __name__ __main__: try: velocity_control_node() except rospy.ROSInterruptException: pass注意即便使用了on_shutdown如果你的这台电脑突然死机、断电、或者网线被拔掉这段 Python 代码根本来不及执行机器人依然会维持最后的速度失控运转。