Exercise 5.b Inverse dynamics and impedance control
Inverse dynamics is the problem of computing the joint torques of a robot given its joint positions, velocities and accelerations: \bm{\tau} = \bm{M}(\bm{q})\bm{\ddot{q}}+ \bm{C}(\bm{q},\bm{\dot{q}}) + \bm{g}(\bm{q}).
These are physical models that allow us to control the motion of a robot. You can read about inverse dynamics in Section 6 of the RCFS documentation.
The goal of this exercise is to understand the terms in the inverse dynamics formulation and to control the robot to reach a desired position using joint space impedance control.
The function inverse_dynamics(q, dq, ddq, param) implements the inverse dynamics model for a planar manipulator. Its outputs are joint torques.
The function controlCommand(state, param) takes the current state of the robot [\bm{q}, \bm{\dot{q}}] as input and outputs joint torque commands that are sent to the robot.
Set \bm{q}, \bm{\dot{q}} and \bm{\ddot{q}} so that \bm{\tau} = \bm{g}(\bm{q}). Perturb the robot with the mouse and observe the result of the perturbation.
Set \bm{q}, \bm{\dot{q}} and \bm{\ddot{q}} so that \bm{\tau} = \bm{C}(\bm{q},\bm{\dot{q}}) + \bm{g}(\bm{q}). Perturb the robot with the mouse and observe the result of the perturbation.
We would like the robot to reach an upright position q_target = np.array([np.pi/2, 0]) and stay there with zero velocity dq_target = np.array([0, 0]).
Set \bm{q}, \bm{\dot{q}} and \bm{\ddot{q}} such that we implement the following impedance controller to achieve our goal: \bm{\tau} = \bm{M}(\bm{q})(\bm{K}_p(\bm{q}^d - \bm{q}) + \bm{K}_v(\bm{\dot{q}}^d - \bm{\dot{q}})) + \bm{C}(\bm{q},\bm{\dot{q}}) + \bm{g}(\bm{q}).
You should see that it stabilizes around the upright position. To check how stable is your controller, try to perturb the robot with the mouse.
Modify the values of stiffness and damping to see the effect of perturbations on the impedance controller.
q_target = np.array([np.pi/2, 0])
dq_target = np.array([0, 0])
Kp = 10
Kv = 1
def controlCommand(state, param=param):
# Question 1: Gravity Compensation Term (g(q))
q = np.zeros(param.nbVarX) # Implement here
dq = np.zeros(param.nbVarX) # Implement here
ddq = np.zeros(param.nbVarX) # Implement here
u = inverse_dynamics(q, dq, ddq, param=param)
# Question 2: Gravity compensation and coriolis terms (c(q,dq) + g(q))
q = np.zeros(param.nbVarX) # Implement here
dq = np.zeros(param.nbVarX) # Implement here
ddq = np.zeros(param.nbVarX) # Implement here
u = inverse_dynamics(q, dq, ddq, param=param)
# Question 3: Joint impedance control for reaching upright position
q = np.zeros(param.nbVarX) # Implement here
dq = np.zeros(param.nbVarX) # Implement here
ddq = np.zeros(param.nbVarX) # Implement here
u = inverse_dynamics(q, dq, ddq, param=param) # implement here
return u
print(state)
def controlCommand(state, param=param):
# Question 1: Gravity Compensation Term (g(q))
q = state[:param.nbVarX]
dq = np.zeros(param.nbVarX)
ddq = np.zeros(param.nbVarX)
u = inverse_dynamics(q, dq, ddq, param=param)
return u
print(state)