Force Control Applications
Overview
The value of force sensing is ultimately realized in control applications. This section introduces core applications of force sensing in robot control: force-controlled grasping, impedance control, admittance control, collision detection, and force-guided assembly.
Force-Controlled Grasping
Grip Force Regulation
Goal: Apply just enough grip force -- neither dropping nor damaging the object.
Minimum grip force condition (parallel gripper, two-finger contact):
where:
- \(F_{load}\) is the external load (typically object weight \(mg\); during acceleration \(m(g + a)\))
- \(\mu\) is the friction coefficient between fingers and object
- Factor of 2 accounts for two contact surfaces
With safety factor:
Typical safety factor \(k_s = 1.5 \sim 2.0\).
Slip Detection
When slipping occurs, the force sensor detects the following characteristic signals:
Based on tangential force ratio:
When \(r \to \mu\) (approaching the friction cone boundary), slip is imminent.
Based on vibration:
Slip generates high-frequency vibration signals (typically 50-500 Hz), detectable through the AC component of tactile sensors:
Adaptive Grip Control:
def adaptive_grip_control(F_sensor, F_grip_current):
"""
Adaptive grip control based on slip detection
"""
F_normal = F_sensor.z
F_tangential = sqrt(F_sensor.x**2 + F_sensor.y**2)
# Friction ratio
friction_ratio = F_tangential / (F_normal + 1e-6)
# Safety margin
safety_margin = mu_estimated - friction_ratio
if safety_margin < SAFETY_THRESHOLD:
# Approaching slip, increase grip force
F_grip_new = F_grip_current + GRIP_INCREMENT
elif safety_margin > 2 * SAFETY_THRESHOLD:
# Sufficient margin, can reduce grip force (save energy/protect object)
F_grip_new = F_grip_current - GRIP_DECREMENT
else:
F_grip_new = F_grip_current
return clip(F_grip_new, F_GRIP_MIN, F_GRIP_MAX)
Impedance Control
Basic Concept
Impedance control makes the robot end-effector behave with desired "spring-damper-mass" dynamics:
where:
- \(e = x - x_d\) is the position error (current position - desired position)
- \(M_d \in \mathbb{R}^{6 \times 6}\) is the desired inertia matrix
- \(D_d \in \mathbb{R}^{6 \times 6}\) is the desired damping matrix
- \(K_d \in \mathbb{R}^{6 \times 6}\) is the desired stiffness matrix
- \(F_{ext}\) is the external contact force
Physical Intuition
| Parameter | Effect of Increasing | Typical Scenario |
|---|---|---|
| Large \(K_d\) | Robot is "stiff," resists displacement | Precision positioning |
| Small \(K_d\) | Robot is "soft," compliant to external force | Safe interaction |
| Large \(D_d\) | Motion is damped, slow response | Vibration suppression |
| Large \(M_d\) | Large inertia, hard to push | Heavy-load handling |
Joint-Space Impedance Control
Mapping the impedance relationship to joint space:
Control law:
where \(K_q, D_q\) are joint-space stiffness and damping matrices.
Cartesian-Space Impedance Control
More intuitive -- directly specifying impedance behavior in task space:
Important Notes:
- Requires accurate kinematic model (\(J(q)\), \(x = f(q)\))
- Dynamics compensation (gravity \(g(q)\)) improves performance
- Special handling needed near singularities
Variable Stiffness Control
Adjusting stiffness online according to task requirements:
Smooth transition:
where \(\sigma\) is the sigmoid function.
Admittance Control
Difference from Impedance Control
| Aspect | Impedance Control | Admittance Control |
|---|---|---|
| Input | Position deviation -> Output force | External force -> Output position deviation |
| Causality | \(F = Z \cdot v\) (Force = Impedance × Velocity) | \(v = Y \cdot F\) (Velocity = Admittance × Force) |
| Suitable For | Torque-controllable joints | Position-controlled robots |
| Sensor Requirement | Force sensor optional | Force sensor required |
| Inner Loop | Torque control | Position/Velocity control |
Admittance Controller
The force sensor measures external force \(F_{ext}\), and the admittance controller computes position correction:
Then the correction is superimposed on the desired trajectory:
class AdmittanceController:
def __init__(self, M, D, K, dt):
self.M = M # Desired inertia
self.D = D # Desired damping
self.K = K # Desired stiffness
self.dt = dt
self.x_adj = np.zeros(6)
self.dx_adj = np.zeros(6)
def update(self, F_ext, x_desired):
# Admittance dynamics: M * ddx + D * dx + K * x = F_ext
ddx_adj = np.linalg.solve(self.M,
F_ext - self.D @ self.dx_adj - self.K @ self.x_adj)
# Integration
self.dx_adj += ddx_adj * self.dt
self.x_adj += self.dx_adj * self.dt
# Superimpose on desired position
x_cmd = x_desired + self.x_adj
return x_cmd
Application: Human-Robot Collaborative Carrying
A human pushes the robot end-effector, and the robot compliantly moves:
- \(K_d = 0\) (no spring restoring force, free movement)
- \(D_d\) moderate (damping provides stability and a "weight feel")
- \(M_d\) small (small inertia, easy to push)
This is the simplest admittance control -- the human applies force, and the robot moves proportionally.
Collision Detection
Momentum Observer
The momentum observer is a collision detection method that does not require an external force sensor (though having one improves accuracy).
Generalized momentum:
Rate of momentum change:
Using the property that \(\dot{M} - 2C\) is skew-symmetric:
Observer:
where \(K_I > 0\) is the observer gain. At steady state:
The observer output converges to the external torque.
Collision Judgment
Collision Response Strategies:
| Level | Condition | Response |
|---|---|---|
| Warning | \(\|\hat{\tau}_{ext}\| > \tau_1\) | Decelerate |
| Soft stop | \(\|\hat{\tau}_{ext}\| > \tau_2\) | Stop motion |
| Emergency stop | \(\|\hat{\tau}_{ext}\| > \tau_3\) | Cut motor drive |
| Retreat | After soft stop | Back away along collision direction |
Improving Sensitivity
Collision detection sensitivity depends on:
- Model accuracy: Inaccurate friction model -> large residual -> low sensitivity
- Sensor noise: Encoder noise -> threshold cannot be set too low
- Sampling rate: Higher is better (1 kHz or above recommended)
- Filtering: Low-pass filtering reduces false alarms but increases latency
Force-Guided Assembly
Peg-in-Hole Assembly
A classic force-controlled assembly task and the killer application for 6-axis F/T sensors.
Challenges:
- Tight clearance (possibly only 0.01-0.1 mm)
- Pure position control cannot accomplish this (positioning accuracy insufficient)
- Force feedback is needed to guide alignment
Three-Phase Strategy:
Phase 1: Approach and Search
Spiral search to locate the hole:
Simultaneously apply constant downward force \(F_z = F_{search}\).
Detection condition: When \(F_z\) suddenly decreases (peg enters the hole opening) -> advance to next phase.
Phase 2: Alignment
Adjust orientation based on torque signals:
Torques \(M_x, M_y\) reflect the angular misalignment between peg and hole.
Convergence condition: \(\sqrt{M_x^2 + M_y^2} < M_{tolerance}\)
Phase 3: Insertion
Maintain orientation, apply constant force along the Z direction:
Simultaneously zero lateral forces (admittance control):
Completion condition: \(z > z_{target}\) or \(F_z > F_{max}\) (jammed).
Surface Tracking
Force sensors enable the robot to move along an unknown surface while maintaining constant contact force:
Hybrid Force/Position Control:
where:
- \(S_f = \text{diag}(0,0,1,0,0,0)\) -- Force control direction selection matrix
- \(S_p = I - S_f\) -- Position control direction selection matrix
- Normal direction (z) uses force control, tangential directions (x, y) use position control
Screw Tightening
A typical torque control application:
- Free run-in phase: Velocity control, low torque
- Seating phase: Torque begins to rise
- Tightening phase: Torque control, reach target torque
Over-tightening protection: \(M_z > M_{max} \Rightarrow \text{stop}\)
Force Control + Learning
Learning Impedance Parameters
Traditional methods require manual tuning of \(K_d, D_d, M_d\); reinforcement learning can learn them automatically:
State \(s\) includes position, velocity, and force information.
Residual Force Learning
Superimpose learned force corrections on top of model-based control:
Related Content
- Control Theory -- Control theory fundamentals
- 6-Axis Force/Torque Sensor -- F/T sensor hardware
- Force Sensing Overview -- Complete picture of force sensing
References
- Siciliano, B. et al., Robotics: Modelling, Planning and Control, Ch. 9
- Hogan, N., "Impedance Control: An Approach to Manipulation," 1985
- De Luca, A. et al., "Collision Detection and Safe Reaction with the DLR-III Lightweight Manipulator Arm," IROS, 2006
- Inoue, T. et al., "Robotic Peg-in-Hole Assembly: State of the Art Review," Advanced Robotics, 2017