This raises the question: How can we manually guide the robot while it is in FCI mode?
Tip
If you only care about the โhowโ(the implementation) and not the โwhyโ, feel free to skip the remaining sections, head directly to my repo, and follow the README.md to set up the stack.
kpโ: the proportional gain (think of this as stiffness or a โspringโ).
kdโ: the derivative gain (think of this as damping or โfrictionโ).
The Zero-Gravity Configuration
How can we make the Franka feel like itโs floating in zero gravity? The key idea is to command the motors to only counteract gravity, without trying to hold a specific position.
It turns out we only need to modify a few lines in the ros2_controller (ros2_control) configuration:
โญ๏ธRegardless of the current joint positions(q) or joint velocities(qหโ), the controller will not apply torque to move the arm.
โญ๏ธRegardless of the desired joint positions (qd) or desired joint velocities (qหโd), the controller ignores them.
The robot simply stays thereโฆ unaffected by the world around itโฆ It exerts no effort to moveโฆ
The Complete Controller Equation
The previous section builds up an intuition for how setting kpโ=0 and kdโ=0 leads to a โfloatingโ state. However, it hides some underlying complexity.
First, when I physically move the robot, I am interacting with it in Cartesian space (task space). Therefore, the controller should technically be formulated in task space
ฯtaskโ,
rather than joint space:
ฯ=kpโ(qdโq)+kdโ(qหโdโqหโ)โ.
Additionally, the task torque ฯtaskโ is just one part of the total commanded torque. There are several other components acting behind the scenes to keep the robot stable and safe. The complete equation looks like this:
where ฯdโโRn is the desired joint torque vector sent to the actuators, and n=7 since the Franka Research 3 has 7 joints.
In our โfloatingโ scenario, we simply set the gains of ฯtaskโ to 0. The remaining ฯ components are responsible for maintaining the robot in โzero gravityโ.
J(q)โR6รn denotes Jacobian matrix mapping joint velocities qหโ to end-effector spatial velocitiesxห=Jqหโ. Its transposeJT maps Cartesian wrenches to joint torques.
KxโโR6ร6 denotes stiffness matrix where the diagonal entries are the spring constants in task space: Kxโ=diag(kpxโโ,kpyโโ,kpzโโ,krxโโ,kryโโ,krzโโ). These are intentionally set to 0 in โfloatingโ mode.
DxโโR6ร6 denotes damping matrix. The diagonal entries are damping constants: Dxโ=diag(dpxโโ,โฆ,drzโโ). They often defaults to diโ=2kiโโ (critical damping).
eโR6 denotes the task-space error.
ฮxโโR6ร6 denotes operational-space inertia, defined as ฮxโ=(JMโ1JT)โ1 .
Error computation: e
The spatial error e can be calculated either in the local end-effector frame E:
The nullspace projectorN(q)โRnรn projects torques into a space that does not affect the end-effectorโs Cartesian motion. It has three common variants:
Dynamic:NE=InโโJTJหT, where Jห=Mโ1JTฮxโ is the dynamically consistent pseudoinverse.
Kinematic:NE=InโโJโ J, where Jโ is the standard Moore-Penrose pseudoinverse.
None:NE=Inโ (direct joint space control with no projection).
Gravity Compensation: ฯgโ
ฯgโ=g(q)
The g(q)โRn is the generalized gravity vector (often computed via RNEA in Pinocchio). It provides the exact torque required at each joint to counteract the gravitational forces on all links.
Tip
This is the critical term that actually keeps the robot โfloatingโ when task stiffness is zero.
Coriolis Compensation: ฯcorโ
ฯcorโ=C(q,qหโ)qหโ
The Coriolis matrixC(q,qหโ)โRnรn captures the velocity-dependent forces arising from the joint coupling.
Warning
Without this term, a fast-moving robot would โdriftโ because centrifugal and Coriolis forces would go uncompensated.