Logo Xingxin on Bug

How to Enable Zero-Gravity Teleoperating a Franka Robot?

March 22, 2026
9 min read

Recently, I have been working on teleoperating a Franka Research 3 robot, aiming for the smooth mobility seen in the official video demos.

The results are promising: I can move the robot freely. It feels weightless, as if it is โ€œfloatingโ€ in the air and completely at my disposal.

Because it is so compliant, I can grab the end-effector and guide it by hand - a technique known as kinesthetic teaching. At the same time, I can read the joint position values in real time.

Normally, this level of mobility is only available when using the default Guiding Mode.

Guiding ModeFCI Mode

However, in Guiding Mode (indicated by a white LED), you cannot use the franka_ros2: ROS 2 integration for Franka research robots to read the joint positions via libfranka: C++ library for Franka Robotics research robots. To do that, the robot must be in FCI Mode (indicated by a green LED ๐ŸŸฉ) and I didnโ€™t press the guiding button.

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.

A Quick Review of the PD Controller

In a previous post, I built an intuition for PID controller at Understanding PD Controllers in Robotics and Robot Learning. In joint space, a PD controller can be expressed as:

ฯ„=kp(qdโˆ’q)โŸP+kiโˆซ(qdโˆ’q)dtโŸI+kd(qห™dโˆ’qห™)โŸD.\tau = \underbrace{k_p (q^d - q)}_{P} + \underbrace{k_i \int (q^d - q) dt}_{I} + \underbrace{k_d (\dot{q}^d - \dot{q})}_{D}.

where

  • ฯ„\tau: the command sent to the actuator (pulse-width modulation), simplified here as torque.
  • qq: the current actual joint position.
  • qdq^d: the desired joint position (target).
  • (qdโˆ’q)(q^d - q): the position error.
  • qห™\dot{q}: the current actual joint velocity.
  • qห™d\dot{q}^d: the desired joint velocity (target).
  • (qห™dโˆ’qห™)(\dot{q}^d - \dot{q}): the velocity error.
  • kpk_p: the proportional gain (think of this as stiffness or a โ€œspringโ€).
  • kdk_d: 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:

task:
  k_pos_x: 0.0
  k_pos_y: 0.0
  k_pos_z: 0.0

I originally found this trick in CRISP - Compliant ROS2 Controllers for Learning-Based Manipulation Policies. I didnโ€™t fully grasp it at first, but once I expanded the math, it made perfect sense. Intuitively, it looks like this:

ฯ„=kp(qdโˆ’q)โŸP+kd(qห™dโˆ’qห™)โŸD=kp(qdโˆ’q)โŸP+kd(qห™dโˆ’qห™)โŸD=0(qdโˆ’q)+0(qห™dโˆ’qห™)=0.\begin{align} \tau &= \underbrace{k_p (q^d - q)}_{P} + \underbrace{k_d (\dot{q}^d - \dot{q})}_{D}\\ &= \underbrace{\cancel{k_p} (q^d - q)}_{P} + \underbrace{\cancel{k_d} (\dot{q}^d - \dot{q})}_{D}\\ &= 0(q^d - q) + 0(\dot{q}^d - \dot{q}) \\ &= 0. \end{align}

It essentially says:

  • โญ๏ธRegardless of the current joint positions(qq) or joint velocities(qห™\dot{q}), the controller will not apply torque to move the arm.
  • โญ๏ธRegardless of the desired joint positions (qdq^d) or desired joint velocities (qห™d\dot{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=0k_p=0 and kd=0k_d=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โ€‰โ€‰,\tau_{\text{task}} \,\,,

rather than joint space:

ฯ„=kp(qdโˆ’q)+kd(qห™dโˆ’qห™).\xcancel{\tau = k_p (q^d - q) + k_d (\dot{q}^d - \dot{q})}.

Additionally, the task torque ฯ„task\tau_{\text{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:

ฯ„d=ฯ„taskโŸprimaryย task+ฯ„nullโŸnullspace+ฯ„fricโŸfriction+ฯ„corโŸCoriolis+ฯ„gโŸgravity+ฯ„limโŸjointย limits+ฯ„extโŸexternalย wrench\tau_d = \underbrace{\color{blue}{\tau_{\text{task}}}}_{\text{primary task}} + \underbrace{\color{red}{\tau_{\text{null}}}}_{\text{nullspace}} + \underbrace{\color{red}{\tau_{\text{fric}}}}_{\text{friction}} + \underbrace{\color{red}{\tau_{\text{cor}}}}_{\text{Coriolis}} + \underbrace{\color{red}{\tau_g}}_{\text{gravity}} + \underbrace{\color{red}{\tau_{\text{lim}}}}_{\text{joint limits}} + \underbrace{\color{red}{\tau_{\text{ext}}}}_{\text{external wrench}}

where ฯ„dโˆˆRn\tau_d \in \mathbb{R}^{n} is the desired joint torque vector sent to the actuators, and n=7n = 7 since the Franka Research 3 has 7 joints.

In our โ€œfloatingโ€ scenario, we simply set the gains of ฯ„task\tau_{\text{task}} to 00. The remaining ฯ„\tau components are responsible for maintaining the robot in โ€œzero gravityโ€.

ฯ„d=ฯ„taskโŸprimaryย task+ฯ„nullโŸnullspace+ฯ„fricโŸfriction+ฯ„corโŸCoriolis+ฯ„gโŸgravity+ฯ„limโŸjointย limits+ฯ„extโŸexternalย wrench\tau_d = \cancel{\underbrace{\color{blue}{\tau_{\text{task}}}}_{\text{primary task}}} + \underbrace{\color{red}{\tau_{\text{null}}}}_{\text{nullspace}} + \underbrace{\color{red}{\tau_{\text{fric}}}}_{\text{friction}} + \underbrace{\color{red}{\tau_{\text{cor}}}}_{\text{Coriolis}} + \underbrace{\color{red}{\tau_g}}_{\text{gravity}} + \underbrace{\color{red}{\tau_{\text{lim}}}}_{\text{joint limits}} + \underbrace{\color{red}{\tau_{\text{ext}}}}_{\text{external wrench}}
Remark

Unless otherwise stated, the mathematical notation in the remaining sections follows Russ Tedrakeโ€™s conventions in Robotic Manipulation.

Task-Space Impedance Torque: ฯ„task\tau_{\text{task}}

This can be expressed either in standard form:

ฯ„task=J(q)T[Kxโ€‰eโˆ’Dxโ€‰J(q)โ€‰qห™],\tau_{\text{task}} = J(q)^T \left[ K_x \, e - D_x \, J(q) \, \dot{q} \right],

or in Khatibโ€™s operational-space form:

ฯ„task=J(q)Tโ€‰ฮ›x[Kxโ€‰eโˆ’Dxโ€‰J(q)โ€‰qห™].\tau_{\text{task}} = J(q)^T \, \Lambda_x \left[ K_x \, e - D_x \, J(q) \, \dot{q} \right].

where

  • qโˆˆRnq \in \mathbb{R}^n denotes joint positions. It is often passed through EMA filter. A statistics tool that is used in quantitative trading quite a lot.
  • qห™โˆˆRn\dot{q} \in \mathbb{R}^n denotes joint velocities.
  • J(q)โˆˆR6ร—nJ(q) \in \mathbb{R}^{6 \times n} denotes Jacobian matrix mapping joint velocities qห™\dot{q} to end-effector spatial velocities xห™=Jqห™\dot{x} = J\dot{q}. Its transpose JTJ^T maps Cartesian wrenches to joint torques.
  • KxโˆˆR6ร—6K_x \in \mathbb{R}^{6 \times 6} denotes stiffness matrix where the diagonal entries are the spring constants in task space: Kx=diag(kpx,kpy,kpz,krx,kry,krz)K_x = \text{diag}(k_{p_x}, k_{p_y}, k_{p_z}, k_{r_x}, k_{r_y}, k_{r_z}). These are intentionally set to 0 in โ€œfloatingโ€ mode.
  • DxโˆˆR6ร—6D_x \in \mathbb{R}^{6 \times 6} denotes damping matrix. The diagonal entries are damping constants: Dx=diag(dpx,โ€ฆ,drz)D_x = \text{diag}(d_{p_x},\ldots,d_{r_z}). They often defaults to di=2kid_i = 2\sqrt{k_i} (critical damping).
  • eโˆˆR6e \in \mathbb{R}^6 denotes the task-space error.
  • ฮ›xโˆˆR6ร—6\Lambda_x \in \mathbb{R}^{6 \times 6} denotes operational-space inertia, defined as ฮ›x=(JMโˆ’1JT)โˆ’1\Lambda_x = (J M^{-1} J^T)^{-1} .

Error computation: ee

The spatial error ee can be calculated either in the local end-effector frame EE:

e=[ERWโ€‰(WpDโˆ’WpE)Elogโก3(ERWโ€‰WRD)]=[EpDEฯ•D],e = \begin{bmatrix} {^E R^W} \, ({^W p^D} - {^W p^E})_E \\ \log_3({^E R^W} \, {^W R^D}) \end{bmatrix} = \begin{bmatrix} {^E p^D} \\ {^E \phi^D} \end{bmatrix},

or in the world frame WW:

e=[WpDโˆ’WpElogโก3(WRDโ€‰(WRE)T)].e = \begin{bmatrix} {^W p^D} - {^W p^E} \\ \log_3({^W R^D} \, ({^W R^E})^T) \end{bmatrix} .
Remark

The notation here is rigorous to avoid ambiguity.

  • WpDโˆˆR3{^W p^D} \in \mathbb{R}^3 denotes the desired position of target frame DD measured from world frame WW, expressed in WW.
  • WpEโˆˆR3{^W p^E} \in \mathbb{R}^3 denotes the current end-effector position measured from WW, expressed in WW
  • WRDโˆˆSO(3){^W R^D} \in SO(3) denotes the desired orientation of DD measured from WW, the SO(3)SO(3) refers to special orthogonal group.
  • ERW=(WRE)T{^E R^W} = ({^W R^E})^T denotes the current inverse rotation of the end-effector.
  • logโก3(โ‹…)\log_3(\cdot) denotes a logarithmic map such that SO(3)โ†’R3SO(3) \to \mathbb{R}^3, which extracts the axis-angle rotation error vector.

Nullspace Torque: ฯ„null\tau_{\text{null}}

ฯ„null=clipโ€‰โฃ(NE(q)[Kns(qdโˆ’q)+Dns(qห™dโˆ’qห™)]โŸฯ„secondary,โ€…โ€Šโˆ’ฯ„ns,max,โ€…โ€Šฯ„ns,max)\tau_{\text{null}} = \text{clip}\!\Big( N^E(q) \underbrace{\left[ K_{\text{ns}} (q^d - q) + D_{\text{ns}} (\dot{q}^d - \dot{q}) \right]}_{\tau_{\text{secondary}}},\; -\tau_{\text{ns,max}},\; \tau_{\text{ns,max}} \Big)

The nullspace projector N(q)โˆˆRnร—nN(q) \in \mathbb{R}^{n \times 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ห‰TN^E = I_n - J^T \bar{J}^T, where Jห‰=Mโˆ’1JTฮ›x\bar{J} = M^{-1} J^T \Lambda_x is the dynamically consistent pseudoinverse.
  • Kinematic: NE=Inโˆ’Jโ€ JN^E = I_n - J^\dagger J, where Jโ€ J^\dagger is the standard Moore-Penrose pseudoinverse.
  • None: NE=InN^E = I_n (direct joint space control with no projection).

Gravity Compensation: ฯ„g\tau_g

ฯ„g=g(q)\tau_g = g(q)

The g(q)โˆˆRng(q) \in \mathbb{R}^n 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\tau_{\text{cor}}

ฯ„cor=C(q,qห™)โ€‰qห™\tau_{\text{cor}} = C(q, \dot{q}) \, \dot{q}

The Coriolis matrix C(q,qห™)โˆˆRnร—nC(q,\dot{q}) \in \mathbb{R}^{n \times 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.

Friction Compensation: ฯ„fric\tau_{\text{fric}}

ฯ„fric,i=a1,i1+eโˆ’a2,i(qห™i+a3,i)โˆ’a1,i1+eโˆ’a2,iโ€‰a3,i\tau_{\text{fric},i} = \frac{a_{1,i}}{1 + e^{-a_{2,i}(\dot{q}_i + a_{3,i})}} - \frac{a_{1,i}}{1 + e^{-a_{2,i} \, a_{3,i}}}

This is sigmoid-based model provides a smooth approximation of Coulomb friction and viscosity, where

  • a1,ia_{1,i} is the friction amplitude
  • a2,ia_{2,i} is the sigmoid slope
  • a3,ia_{3,i} is the velocity dead-zone shift

Joint Limit Repulsion: ฯ„lim\tau_{\text{lim}}

ฯ„lim,i={ฯ„maxโกโ‹…ฮดsafeโˆ’(qiโˆ’qiminโก)ฮดsafeifย qiโˆ’qiminโก<ฮดsafeโˆ’ฯ„maxโกโ‹…ฮดsafeโˆ’(qimaxโกโˆ’qi)ฮดsafeifย qimaxโกโˆ’qi<ฮดsafe0otherwise\tau_{\text{lim},i} = \begin{cases} \tau_{\max} \cdot \dfrac{\delta_{\text{safe}} - (q_i - q_i^{\min})}{\delta_{\text{safe}}} & \text{if } q_i - q_i^{\min} < \delta_{\text{safe}} \\[8pt] -\tau_{\max} \cdot \dfrac{\delta_{\text{safe}} - (q_i^{\max} - q_i)}{\delta_{\text{safe}}} & \text{if } q_i^{\max} - q_i < \delta_{\text{safe}} \\[8pt] 0 & \text{otherwise} \end{cases}

This creates a virtual โ€œwallโ€ that linearly ramps up repulsion torque as a joint approaches physical limits(qiminโก,qimaxโกq_i^{\min}, q_i^{\max}) where

  • ฮดsafe\delta_{\text{safe}} denotes the safe range threshold, e.g. 0.3 rad.
  • ฯ„maxโก\tau_{\max} denotes the maximum repulsion torque, e.g. 5.0 Nm.
Remark

See Understanding Franka Robot Control Parameters for more on the limits of a Franka Research 3.

External Wrench: ฯ„ext\tau_{\text{ext}}

ฯ„ext=J(q)Tโ€‰Fext\tau_{\text{ext}} = J(q)^T \, \mathcal{F}_{\text{ext}}

where

FextโˆˆR6=[fx,fy,fz,mx,my,mz]T\mathcal{F}_{\text{ext}} \in \mathbb{R}^6 = [f_x, f_y, f_z, m_x, m_y, m_z]^T

represents external forces and torques applied to the end-effector.

Post-Processing and Safety

Before sending commands to the motors, two safety filters are applied to ฯ„d\tau_d:

  1. Torque Rate Saturation: Limits โˆฅฯ„dโˆ’ฯ„dprevโˆฅ\|\tau_d - \tau_d^{\text{prev}}\| per timestep to prevent sudden, discontinuous torque spikes.
  2. Exponential Moving Average (EMA): ฯ„dโ†ฮฑโ€‰ฯ„dprev+(1โˆ’ฮฑ)โ€‰ฯ„d\tau_d \leftarrow \alpha \, \tau_d^{\text{prev}} + (1 - \alpha) \, \tau_d to smooth the output signal over time.

The Manipulator Equation

All of these model-based terms (MM, CC, ฯ„g\tau_g) stems directly from the fundamental manipulator equation of motion:

M(q)qยจ+C(q,qห™)qห™+g(q)=ฯ„+ฯ„ext.M(q)\ddot{q} + C(q,\dot{q})\dot{q} + g(q) = \tau + \tau_{\text{ext}}.

References

See also...