Logo Xingxin on Bug

Understanding Franka Robot Control Parameters

January 18, 2026
10 min read

In this post, I want to break down the control parameters found in the Franka Robotics Documentation.

🗺Big Picture

Think of the relationship between a driver(us) and a car(Franka).

Why do we need to know this parameters as a developer?

As developers, we are the drivers planning a route from point AA to point BB. We must plan a smooth path that doesn’t require slamming on the gas, jerky braking, or taking a sharp turn at high speed.

Why do we need to care about the robot’s limits?

You treat your car well, right? You should treat your robot the same way. However, the Franka robot is more conservative. It constantly checks: “Can my tires🛞 handle this turn at this speed?” If you try to move too fast or too suddenly, the system will intervene. The Franka controller will “abort” and throw an error if you planned an impossible “route”.

✒Notation

Let’s define the notation used in the Franka Control Interface Specification and Robot Limits.


qq

qq refers to joint positions, sometimes called “robot configuration”. It is a 77-vector containing the positions of all joints, measured in radian.

Tip

When you saw qq, you are working in “joint space”.


pp

pp refers to position vector.

Tip

Usually, this describes the end-effector position in Cartesian coordinates.

🧠Intuition

The qq and pp are “static”. On the contrary, their “rate of change”(derivative) are:

  • velocity, 1st derivative
  • acceleration, 2nd derivative
  • jerk, 3rd derivative

Imagine you’re in a car🚗.

  • Velocity is your speed.
  • Acceleration is you pushing the gas pedal.
  • Jerk is how ==suddenly== you slam your foot on the gas or brake pedal.

Then the constraints on these 3 are:

  • (Velocity) p˙,q˙\dot{p},\dot{q}: are you commanding the robot moving too fast?
  • (Acceleration) p¨,q¨\ddot{p},\ddot{q}: are you commanding the robot to speed up or slow down too hard?
  • (Jerk) p...,q...\dddot{p},\dddot{q}: are you commanding the robot to move too suddenly?

Joint trajectory requirements

Necessary conditions

For a command to be accepted, these must be true:

  • qmin<qc<qmaxq_{min} < q_c < q_{max}
  • q˙max<q˙c<q˙max-\dot{q}_{max} < \dot{q}_c < \dot{q}_{max}
  • q¨max<q¨c<q¨max-\ddot{q}_{max} < \ddot{q}_c < \ddot{q}_{max}
  • q...max<q...c<q...max-\dddot{q}_{max} < \dddot{q}_c < \dddot{q}_{max}

Remark

The subscript c_c from the q˙c,q¨c,q...c\dot{q}_c,\ddot{q}_c,\dddot{q}_c denotes the commanded velocity/acceleration/jerk of one specific joint.

Remark

The actual min\min and max\max values refer to Limits for Franka Research 3.

Tip

Recommended conditions are about smoothness.

  • τjmax<τjd<τjmax-{\tau_j}_{max} < {\tau_j}_d < {\tau_j}_{max}
  • τj˙max<τj˙d<τj˙max-\dot{\tau_j}_{max} < \dot{\tau_j}_d < \dot{\tau_j}_{max}

Remark

  • The τ\tau refers to torque.
  • The j_j refers to a specific joint.
  • The d_d refers to desired torque you are asking for.

The amount of torque your command requests from a joint motor should stay below its recommended maximum.”

Warning

Asking for a very sudden change in torque (τd˙\dot{\tau_d} is high) is like yanking a handbrake instead of smoothly pressing a brake pedal. It will “jolt” the robot’s gears, causing vibration.

At the beginning of the trajectory, the following conditions should be fulfilled:

  • q=qcq = q_c
  • q˙c=0\dot{q}_{c} = 0
  • q¨c=0\ddot{q}_{c} = 0

At the end of the trajectory, the following conditions should be fulfilled:

  • q˙c=0\dot{q}_{c} = 0
  • q¨c=0\ddot{q}_{c} = 0

Remark

These conditions are crucial for trajectory generation. If you write your own trajectory generator rather instead of using a framework like MoveIt2, take these conditions seriously.

Tip

The figure in Modern Robotics: Mechanics, Planning, and Control Chapter 9 really illustrates the perfectly.
vel_acc_jerk_traj.svg
Let’s interpret it.

  • q=qcq = q_c: the first commanded joint positions must match the robot’s current measured joint positions.
  • q˙=0\dot{q} = 0: the robot’s speed should be zero at the start and end of the motion.
  • q¨=0\ddot{q}=0: the robot should not be accelerating at the very start and very end.

Cartesian trajectory requirements

Necessary conditions

  • TT must be a proper homogeneous transformation matrix
  • p˙max<pc˙<p˙max-\dot{p}_{max} < \dot{p_c} < \dot{p}_{max} (Cartesian velocity)
  • p¨max<pc¨<p¨max-\ddot{p}_{max} < \ddot{p_c} < \ddot{p}_{max} (Cartesian acceleration)
  • p...max<pc...<p...max-\dddot{p}_{max} < \dddot{p_c} < \dddot{p}_{max} (Cartesian jerk)

Remark

The matrix TT (e.g., O_T_EE in libfranka: C++ library for Franka Robotics research robots) represents the end-effector’s pose. The O_T_EE reads aloud “origin transform to end effector”.
T=[r11r12r13xr21r22r23yr31r32r33z0001]\mathbf{T} = \begin{bmatrix}r_{11} & r_{12} & r_{13} & x \\ r_{21} & r_{22} & r_{23} & y \\ r_{31} & r_{32} & r_{33} & z \\ 0 & 0 & 0 & 1 \end{bmatrix}

  • the last row is [0 0 0 1]
  • the rotation part(top left 3x3) should be orthogonal matrix.

Remark

The pp denotes the position (x,y,zx,y,z) of the end effector.

Remark

The c_c from the p˙c,p¨c,p...c\dot{p}_c,\ddot{p}_c,\dddot{p}_c denotes the commanded velocity/acceleration/jerk.

Conditions derived from inverse kinematics:

  • qmin<qc<qmaxq_{min} < q_c < q_{max}
  • q˙max<qc˙<q˙max-\dot{q}_{max} < \dot{q_c} < \dot{q}_{max}
  • q¨max<qc¨<q¨max-\ddot{q}_{max} < \ddot{q_c} < \ddot{q}_{max}

Conditions derived from inverse kinematics:

  • τjmax<τjd<τjmax-{\tau_j}_{max} < {\tau_j}_d < {\tau_j}_{max}
  • τj˙max<τjd˙<τj˙max-\dot{\tau_j}_{max} < \dot{{\tau_j}_d} < \dot{\tau_j}_{max}

At the beginning of the trajectory, the following conditions should be fulfilled:

  • OTEE=OTEEc{}^OT_{EE} = {{}^OT_{EE}}_c
  • p˙c=0\dot{p}_{c} = 0 (Cartesian velocity)
  • p¨c=0\ddot{p}_{c} = 0 (Cartesian acceleration)

Remark

  • the OTEE{}^OT_{EE} is the robot’s current, measured pose (the 4x4 matrix).
  • the OTEEc{{}^OT_{EE}}_c is the commanded pose your algorithm is sending at the very first step (time = 0).

This is crucial. If the commanded starting pose OTEEc{{}^OT_{EE}}_c is 10cm away from the current pose, the robot would have to instantly jump (teleport) 10cm. This is physically impossible, probably violating the necessary condition.

At the end of the trajectory, the following conditions should be fulfilled:

  • p˙c=0\dot{p}_{c} = 0 (Cartesian velocity)
  • p¨c=0\ddot{p}_{c} = 0 (Cartesian acceleration)

Remark

These are all about smoothness.

Controller requirements

Necessary conditions

  • τj˙max<τjd˙<τj˙max-\dot{\tau_j}_{max} < \dot{{\tau_j}_d} < \dot{\tau_j}_{max}
  • τjmax<τjd<τjmax-{\tau_j}_{max} < {\tau_j}_d < {\tau_j}_{max}

At the beginning of the trajectory, the following conditions should be fulfilled:

  • τjd=0{\tau_j}_{d} = 0

Limits for Franka Research 3

Limits in the Cartesian space are as follows:

NameTranslationRotationElbow
p˙max\dot{p}_{max}3.0ms3.0\frac{\text{m}}{\text{s}}2.5rads2.5\frac{\text{rad}}{\text{s}}2.620rads2.620\frac{\text{rad}}{\text{s}}
p¨max\ddot{p}_{max}9.0ms29.0\frac{\text{m}}{\text{s}^2}17.0rads217.0 \frac{\text{rad}}{\text{s}^2}10.0rads210.0 \frac{\text{rad}}{\text{s}^2}
p...max\dddot{p}_{max}4500.0ms34500.0\frac{\text{m}}{\text{s}^3}8500.0rads38500.0\frac{\text{rad}}{\text{s}^3}5000.0rads35000.0\frac{\text{rad}}{\text{s}^3}

Remark

A limit of 3.0ms3.0\frac{m}{s} means the end-effector’s speed in any direction (x,y,zx, y, z) cannot exceed 3 meters per second.

The 3.03.0 is a peak speed limit. The speed of a trajectory isn’t simple as time = distance / velocity. Think of driving a car for 100 meters. You speed limit is 3m/s, but you can’t drive a car all the way 3m/s. Your speed will be 0m/s at the start and the end.

What really matters to our trajectory generation is: This limit sets a minimum possible time for the motion.

  • if we tell the robot to move 1.5 meters in 0.5 seconds, it would require the speed to be 3m/s for the whole time, this is impossible! The acceleration and jerk limit must be invalid.

Remark

The rotation limits apply to the angular velocity, acceleration, and jerk of the end-effector’s orientation.


Joint space limits are:

NameJoint 1Joint 2Joint 3Joint 4Joint 5Joint 6Joint 7Unit
qmaxq_{max}2.90071.83612.9007-0.11692.87634.62163.0508rad\text{rad}
qminq_{min}-2.9007-1.8361-2.9007-3.0770-2.87630.4398-3.0508rad\text{rad}
q˙max\dot{q}_{max}2.622.622.622.625.264.185.26rads\frac{\text{rad}}{\text{s}}
q¨max\ddot{q}_{max}10101010101010rads2\frac{\text{rad}}{\text{s}^2}
q...max\dddot{q}_{max}5000500050005000500050005000rads3\frac{\text{rad}}{\text{s}^3}
τjmax{\tau_j}_{max}87878787121212Nm\text{Nm}
τj˙max\dot{\tau_j}_{max}1000100010001000100010001000Nms\frac{\text{Nm}}{\text{s}}
q˙offset\dot{q}_{offset}0.65990.25170.20000.35330.57570.48780.4628rads\frac{\text{rad}}{\text{s}}
q¨dec\ddot{q}_{dec}6.02.5853.54.017.05.517.0rads2\frac{\text{rad}}{\text{s}^2}

Remark

  • the q¨dec\ddot{q}_{dec} denotes the Maximum Deceleration Limits, the “braking power”. This value allows the robot to calculate its “stopping distance” (in this case, “stopping angle”). By knowing this guaranteed “braking” power, the controller can figure out when it needs to start telling the joint to slow down so it doesn’t slam into its physical limit (qmaxq_{max}).
  • the q˙offset\dot{q}_{offset} denotes velocity offset, a small “buffer” velocity. A technical tuning parameter. It’s used in that square-root formula to help shape the “ramp” of the slowing-down curve. It helps ensure the velocity limit starts to decrease smoothly before it gets critically close to the joint limit, rather than all at once.

Remark

Note that the maximum joint velocity q˙max\dot{q}_{max} depends on both the joint position and the direction of motion. The position based joint velocity limits are computed by:

qi˙(qi)max=min(q˙max,i,max(0,  q˙offset,i+max(0,  2q¨dec,i(qmax,iqi))))qi˙(qi)min=max(q˙min,i,min(0,  q˙offset,imax(0,  2q¨dec,i(qmin,i+qi))))\begin{aligned} \dot{q_i} (q_i)_{max} &= \min(\dot{q}_{max,i}, \max(0, \; -\dot{q}_{offset,i} + \sqrt{\max(0, \; 2 \cdot \ddot{q}_{dec,i} \cdot (q_{max,i} - q_i))})) \\ \dot{q_i} (q_i)_{min} &= \max(\dot{q}_{min,i}, \min(0, \; \dot{q}_{offset,i} - \sqrt{\max(0, \; 2 \cdot \ddot{q}_{dec,i} \cdot (-q_{min,i} + q_i))})) \end{aligned}

where:

  • qi˙(qi)max\dot{q_i} (q_i)_{max} is the maximum joint velocity for joint ii at position qiq_i.
  • qi˙(qi)min\dot{q_i} (q_i)_{min} is the minimum joint velocity for joint ii at position qiq_i.
  • q˙max,i\dot{q}_{max,i} is the maximum joint velocity for joint ii from the table above.
  • q˙min,i\dot{q}_{min,i} is the minimum joint velocity for joint ii. (simply q˙max,i-\dot{q}_{max,i})
  • q˙offset,i\dot{q}_{offset,i} is the velocity offset for joint ii from the table above.
  • q¨dec,i\ddot{q}_{dec,i} is the maximum deceleration limits for joint ii from the table above.
  • qmax,iq_{max,i} is the maximum joint position for joint ii from the table above.
  • qmin,iq_{min,i} is the minimum joint position for joint ii from the table above.
  • qiq_i is the current joint position of joint ii.
Tip

Since we have this contradiction:

What should we do then?

  • use the above formula. (libfranka has a wrapper for us.)
  • use the following heuristic table

Heuristic Optimal Limits

NameJoint 1Joint 2Joint 3Joint 4Joint 5Joint 6Joint 7Unit
qmaxq_{max}2.34761.54542.4937-0.42262.51004.28412.7045rad\text{rad}
qminq_{min}-2.3476-1.5454-2.4937-2.7714-2.51000.7773-2.7045rad\text{rad}
q˙max\dot{q}_{max}211.51.2531.53rads\frac{\text{rad}}{\text{s}}
q¨max\ddot{q}_{max}10101010101010rads2\frac{\text{rad}}{\text{s}^2}
q...max\dddot{q}_{max}5000500050005000500050005000rads3\frac{\text{rad}}{\text{s}^3}

Compared to the “theoretical” limits, these values are more conservative. I use them quite a lot.