实时命令
实时命令基于 UDP,需要 1kHz 连接到 Control。有两种类型的实时接口:
运动生成器,它定义了关节或笛卡尔空间中的机器人运动。
控制器,定义要发送到机器人关节的扭矩。
有 4 种不同类型的外部运动生成器和 3 种不同类型的控制器(1 个外部和 2 个内部),如下图所示:

实时接口:运动生成器和控制器。
可以使用单个接口或组合两种不同的类型。具体来说,可以给出命令:
只有一个运动生成器,因此使用两个内部控制器之一来跟随命令的运动。
只有一个外部控制器,而忽略任何运动生成器信号,即仅转矩控制。
一个运动生成器和一个外部控制器,可在外部控制器中使用 Control 的逆运动学。
所有实时循环(运动生成器或控制器)都由一个回调函数定义,该函数接收机器人状态和最后一个循环的持续时间(除非发生数据包丢失,否则为 1ms) 并返回接口的特定类型。然后 franka::Robot 类的 control 方法将通过以 1kHz
的频率执行回调函数来运行控制循环,如本例所示
std::function<franka::Torques(const franka::RobotState&, franka::Duration)> my_external_controller_callback;// Define my_external_controller_callback...std::function<franka::JointVelocities(const franka::RobotState&, franka::Duration)> my_external_motion_generator_callback;// Define my_external_motion_generator_callback...try { franka::Robot robot("<fci-ip>"); // only a motion generator robot.control(my_external_motion_generator_callback); // only an external controller robot.control(my_external_controller_callback); // a motion generator and an external controller robot.control(my_external_motion_generator_callback, my_external_controller_callback);} catch (franka::Exception const& e) { std::cout << e.what() << std::endl; return -1;} return 0;}当实时命令 motion_finished 的标志设置为 true 时,表示所有控制循环就完成了。此处展示了 libfranka
示例 中包含的 generate_joint_velocity_motion 示例的代码片段
robot.control( [=, &time](const franka::RobotState&, franka::Duration period) -> franka::JointVelocities { time += period.toSec(); double cycle = std::floor(std::pow(-1.0, (time - std::fmod(time, time_max)) / time_max)); double omega = cycle * omega_max / 2.0 * (1.0 - std::cos(2.0 * M_PI / time_max * time)); franka::JointVelocities velocities = {{0.0, 0.0, 0.0, omega, omega, omega, omega}}; if (time >= 2 * time_max) { std::cout << std::endl << "Finished motion, shutting down example" << std::endl; return franka::MotionFinished(velocities); } return velocities; });在这种情况下,回调函数直接在 robot.control( ... )
函数的调用中定义。它使用关节速度运动生成器接口,因为它返回一个 franka::JointVeloities
对象。它命令最后四个关节的关节速度并将它们移动大约 +/-12 度。在 2 * time_max
秒后,回调函数将返回一个 motion_finished 标志,通过 franka::MotionFinished 方法将它设置为 true
,则控制循环将停止。
请注意,如果仅使用运动生成器,则默认控制器是内部关节阻抗控制器。但是,可以通过设置控制函数的可选参数来使用内部笛卡尔阻抗控制器,例如
// Set joint impedance (optional)robot.setJointImpedance({{3000, 3000, 3000, 3000, 3000, 3000, 3000}});// Runs my_external_motion_generator_callback with the default joint impedance controllerrobot.control(my_external_motion_generator_callback);// Identical to the previous line (default franka::ControllerMode::kJointImpedance)robot.control(my_external_motion_generator_callback, franka::ControllerMode::kJointImpedance);// Set Cartesian impedance (optional)robot.setCartesianImpedance({{2000, 2000, 2000, 100, 100, 100}});// Runs my_external_motion_generator_callback with the Cartesian impedance controllerrobot.control(my_external_motion_generator_callback, franka::ControllerMode::kCartesianImpedance);为了编写控制器,还使用了 franka::Robot::control
函数。以下示例显示了一个简单的控制器,它为每个关节发出零扭矩命令。重力项已由机器人补偿。
robot.control([&](const franka::RobotState&, franka::Duration) -> franka::Torques { return {{0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}}; });您可以在 Libfranka 示例程序
中找到所有接口及控制回路组合的示例。在运行示例之前,请验证机器人是否有足够的自由空间来移动而不会发生碰撞。然后,例如对于 generate_joint_velocity_motion 示例,从 libfranka 构建(build)目录执行以下命令:
./examples/generate_joint_velocity_motion <fci-ip>
警告
要编写自己的运动生成器或控制器,向机器人传递平滑信号至关重要。非平滑信号很容易产生不连续性错误,甚至使机器人不稳定。开始前需 检查 接口规范 。
信号处理
为了便于在非理想网络连接下控制机器人,libfranka 包括信号处理函数,这些函数将修改用户命令的值,使其符合 接口限制。所有实时控制回路中都包含两个 可选功能:
一阶低通滤波器 low-pass filter,用于平滑用户命令信号。
一个速率限制器 rate limiter,它使用户命令值的时间导数饱和。
从版本
0.5.0开始,libfranka 包括一个低通滤波器 low-pass filter,用于 默认运行 的所有实时接口,截止频率为 100Hz。滤波器平滑命令信号以提供更稳定的机器人运动,但不能防止违反 接口限制。从版本
0.4.0开始,所有实时接口的 速率限制器 (rate limiters) 默认运行 。速率限制器 (rate limiters) ,也称为安全控制器 (safe controllers),将限制用户发送的信号的变化率,以防止违反 接口限制。. 对于运动生成器,它将限制加速度和加加速度,而对于外部控制器,它将限制扭矩变化率。它们的主要目的是提高控制回路的稳健性。在数据包丢失的情况下,即使发送的信号符合接口限制,Control 也可能检测到违反速度、加速度或加加速度限制的情况。速率限制将调整命令以确保不会发生这种情况。有关更多详细信息,请查看 不合规错误部分 。小心
速率限制将确保除了逆向运动学之后的关节限制之外没有任何限制被违反,其违反会产生以
cartesian_motion_generator_joint_*开头的一系列错误。有关更多详细信息,请查看 不合规错误部分 。提示
速率限制器中使用的限制在
franka/rate_limiting.h定义并被设置到接口限制中。如果这会产生急动或不稳定的行为,可以将限制设置为较低的值,激活低通滤波器或降低其截止频率。
为了控制信号处理函数,所有 robot.control() 函数调用都有两个额外的可选参数。第一个是启用或停用速率限制器的标志,而第二个指定一阶低通滤波器的截止频率。如果达到截止频率 >=1000.0,滤波器将被停用。例
// Set Cartesian impedance (optional)
robot.setCartesianImpedance({{2000, 2000, 2000, 100, 100, 100}});
// Runs my_external_motion_generator_callback with the Cartesian impedance controller,
// rate limiters on and low-pass filter with 100 Hz cutoff
robot.control(my_external_motion_generator_callback, franka::ControllerMode::kCartesianImpedance);
// Identical to the previous line (default true, 100.0 Hz cutoff)
robot.control(my_external_motion_generator_callback, franka::ControllerMode::kCartesianImpedance, true, 100.0);
// Runs my_external_motion_generator_callback with the Cartesian impedance controller,
// rate limiters off and low-pass filter off
robot.control(my_external_motion_generator_callback, franka::ControllerMode::kCartesianImpedance, false, 1000.0);或类似的外部控制器
// With rate limiting and filter robot.control(my_external_controller); // Identical to the previous line (default true, 100.0 Hz cutoff) robot.control(my_external_controller, true, 100.0); // Without rate limiting but with low-pass filter (100.0 Hz) robot.control(my_external_controller, false); // Without rate limiting and without low-pass filter robot.control(my_external_controller, false, 1000.0);
危险
低通滤波器和速率限制器是用来针对数据包丢失的稳健性功能,在已经设计了平滑运动生成器或控制器 之后 使用。对于新控制回路的首次测试,我们强烈建议停用这些功能。过滤和限制非平滑信号的速率会产生不稳定性或意外行为。太多的数据包丢失也会产生不稳定的行为。通过监控 control_command_success_rate 机器人状态信号来检查通信质量。
内部逻辑
到目前为止,我们已经介绍了在客户端(即自己的工作站 PC)上运行的接口的详细信息。包括实时接口的控制端在内的完整控制回路的行为如下图所示

实时循环:从控制命令到机器人期望的关节扭矩。
运动生成器 :用户发送的所有运动生成器命令都有下标c,代表 ‘commanded’。当发送运动生成器时,机器人运动学完备块Robot Kinematics completion将计算用户命令信号的正向/逆向运动学,产生期望信号,下标d。如果使用内部控制器,它将产生必要的扭矩
提示
当使用 关节 运动生成器时,机器人运动学完备块不会修改命令中的 关节 值,因此
外部控制器:如果发送外部控制器,则用户命令的已经额外补偿重力与摩擦力的期望关节扭矩
其中:
是 libfranka 用户输入的期望扭矩, 是有效控制关节的扭矩, 是补偿电机摩擦的扭矩, 是补偿整个运动学链重力所需的扭矩。
请注意,在控制端,有两件事可以修改信号:
数据包丢失,如果:
在这种情况下,Control 假设一个恒定加速度模型或一个恒定扭矩来推断信号。如果
>=20个数据包连续丢失,则控制循环将停止,并伴随communication_constraints_violation异常的抛出。由于 PC 和 网卡的性能,没有很好的网络连接。
控制回路计算时间太长(取决于网卡和 PC 配置,剩下大约 < 300
的时间用于自己的控制回路)。
提示
如果不确定信号是否被过滤或外插,可以随时检查发送的最后一个命令值,并将它们与在下一个采样中在机器人状态中接收到的值进行比较。还可以在异常发生后在 franka::ControlException::log 成员中找到这些值 。