-
Notifications
You must be signed in to change notification settings - Fork 22
/
Copy pathdiffik_nullspace.py
137 lines (107 loc) · 4.48 KB
/
diffik_nullspace.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
import mujoco
import mujoco.viewer
import numpy as np
import time
# Integration timestep in seconds. This corresponds to the amount of time the joint
# velocities will be integrated for to obtain the desired joint positions.
integration_dt: float = 0.1
# Damping term for the pseudoinverse. This is used to prevent joint velocities from
# becoming too large when the Jacobian is close to singular.
damping: float = 1e-4
# Gains for the twist computation. These should be between 0 and 1. 0 means no
# movement, 1 means move the end-effector to the target in one integration step.
Kpos: float = 0.95
Kori: float = 0.95
# Whether to enable gravity compensation.
gravity_compensation: bool = True
# Simulation timestep in seconds.
dt: float = 0.002
# Nullspace P gain.
Kn = np.asarray([10.0, 10.0, 10.0, 10.0, 5.0, 5.0, 5.0])
# Maximum allowable joint velocity in rad/s.
max_angvel = 0.785
def main() -> None:
assert mujoco.__version__ >= "3.1.0", "Please upgrade to mujoco 3.1.0 or later."
# Load the model and data.
model = mujoco.MjModel.from_xml_path("franka_emika_panda/scene.xml")
data = mujoco.MjData(model)
# Enable gravity compensation. Set to 0.0 to disable.
model.body_gravcomp[:] = float(gravity_compensation)
model.opt.timestep = dt
# End-effector site we wish to control.
site_name = "attachment_site"
site_id = model.site(site_name).id
# Get the dof and actuator ids for the joints we wish to control. These are copied
# from the XML file. Feel free to comment out some joints to see the effect on
# the controller.
joint_names = [
"joint1",
"joint2",
"joint3",
"joint4",
"joint5",
"joint6",
"joint7",
]
dof_ids = np.array([model.joint(name).id for name in joint_names])
actuator_ids = np.array([model.actuator(name).id for name in joint_names])
# Initial joint configuration saved as a keyframe in the XML file.
key_name = "home"
key_id = model.key(key_name).id
q0 = model.key(key_name).qpos
# Mocap body we will control with our mouse.
mocap_name = "target"
mocap_id = model.body(mocap_name).mocapid[0]
# Pre-allocate numpy arrays.
jac = np.zeros((6, model.nv))
diag = damping * np.eye(6)
eye = np.eye(model.nv)
twist = np.zeros(6)
site_quat = np.zeros(4)
site_quat_conj = np.zeros(4)
error_quat = np.zeros(4)
with mujoco.viewer.launch_passive(
model=model,
data=data,
show_left_ui=False,
show_right_ui=False,
) as viewer:
# Reset the simulation.
mujoco.mj_resetDataKeyframe(model, data, key_id)
# Reset the free camera.
mujoco.mjv_defaultFreeCamera(model, viewer.cam)
# Enable site frame visualization.
viewer.opt.frame = mujoco.mjtFrame.mjFRAME_SITE
while viewer.is_running():
step_start = time.time()
# Spatial velocity (aka twist).
dx = data.mocap_pos[mocap_id] - data.site(site_id).xpos
twist[:3] = Kpos * dx / integration_dt
mujoco.mju_mat2Quat(site_quat, data.site(site_id).xmat)
mujoco.mju_negQuat(site_quat_conj, site_quat)
mujoco.mju_mulQuat(error_quat, data.mocap_quat[mocap_id], site_quat_conj)
mujoco.mju_quat2Vel(twist[3:], error_quat, 1.0)
twist[3:] *= Kori / integration_dt
# Jacobian.
mujoco.mj_jacSite(model, data, jac[:3], jac[3:], site_id)
# Damped least squares.
dq = jac.T @ np.linalg.solve(jac @ jac.T + diag, twist)
# Nullspace control biasing joint velocities towards the home configuration.
dq += (eye - np.linalg.pinv(jac) @ jac) @ (Kn * (q0 - data.qpos[dof_ids]))
# Clamp maximum joint velocity.
dq_abs_max = np.abs(dq).max()
if dq_abs_max > max_angvel:
dq *= max_angvel / dq_abs_max
# Integrate joint velocities to obtain joint positions.
q = data.qpos.copy() # Note the copy here is important.
mujoco.mj_integratePos(model, q, dq, integration_dt)
np.clip(q, *model.jnt_range.T, out=q)
# Set the control signal and step the simulation.
data.ctrl[actuator_ids] = q[dof_ids]
mujoco.mj_step(model, data)
viewer.sync()
time_until_next_step = dt - (time.time() - step_start)
if time_until_next_step > 0:
time.sleep(time_until_next_step)
if __name__ == "__main__":
main()