Skip to content

Commit dc6d581

Browse files
committed
Tweak mobile hand examples.
1 parent 17c838f commit dc6d581

File tree

3 files changed

+20
-16
lines changed

3 files changed

+20
-16
lines changed

examples/arm_hand_iiwa_allegro.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -107,8 +107,8 @@ def construct_model() -> mujoco.MjModel:
107107
model, data, f"{finger}_target", f"allegro_left/{finger}", "site"
108108
)
109109

110-
T_eef_prev = configuration.get_transform_frame_to_world(
111-
"attachment_site", "site"
110+
T_palm_prev = configuration.get_transform_frame_to_world(
111+
"allegro_left/palm", "body"
112112
)
113113

114114
rate = RateLimiter(frequency=100.0, warn=False)
@@ -124,11 +124,11 @@ def construct_model() -> mujoco.MjModel:
124124
)
125125
task.set_target(T_pm)
126126

127-
T_eef = configuration.get_transform_frame_to_world(
128-
"attachment_site", "site"
127+
T_palm = configuration.get_transform_frame_to_world(
128+
"allegro_left/palm", "body"
129129
)
130-
T = T_eef @ T_eef_prev.inverse()
131-
T_eef_prev = T_eef.copy()
130+
T = T_palm @ T_palm_prev.inverse()
131+
T_palm_prev = T_palm.copy()
132132
for finger in fingers:
133133
mocap_id = model.body(f"{finger}_target").mocapid[0]
134134
T_w_mocap = mink.SE3.from_mocap_id(data, mocap_id)

examples/arm_hand_xarm_leap.py

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -122,8 +122,8 @@ def construct_model() -> mujoco.MjModel:
122122
model, data, f"{finger}_target", f"leap_right/{finger}", "site"
123123
)
124124

125-
T_eef_prev = configuration.get_transform_frame_to_world(
126-
"attachment_site", "site"
125+
T_palm_prev = configuration.get_transform_frame_to_world(
126+
"leap_right/palm_lower", "body"
127127
)
128128

129129
rate = RateLimiter(frequency=200.0, warn=False)
@@ -146,11 +146,11 @@ def construct_model() -> mujoco.MjModel:
146146
)
147147
task.set_target(T_pm)
148148

149-
T_eef = configuration.get_transform_frame_to_world(
150-
"attachment_site", "site"
149+
T_palm = configuration.get_transform_frame_to_world(
150+
"leap_right/palm_lower", "body"
151151
)
152-
T = T_eef @ T_eef_prev.inverse()
153-
T_eef_prev = T_eef.copy()
152+
T = T_palm @ T_palm_prev.inverse()
153+
T_palm_prev = T_palm.copy()
154154
for finger in fingers:
155155
mocap_id = model.body(f"{finger}_target").mocapid[0]
156156
T_w_mocap = mink.SE3.from_mocap_id(data, mocap_id)

examples/mobile_kinova_leap.py

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -149,7 +149,9 @@ def __call__(self, key: int) -> None:
149149
model, data, f"{finger}_target", f"leap_right/{finger}", "site"
150150
)
151151

152-
T_eef_prev = configuration.get_transform_frame_to_world("pinch_site", "site")
152+
T_palm_prev = configuration.get_transform_frame_to_world(
153+
"leap_right/palm_lower", "body"
154+
)
153155

154156
rate = RateLimiter(frequency=50.0, warn=False)
155157
while viewer.is_running():
@@ -164,9 +166,11 @@ def __call__(self, key: int) -> None:
164166
)
165167
task.set_target(T_pm)
166168

167-
T_eef = configuration.get_transform_frame_to_world("pinch_site", "site")
168-
T = T_eef @ T_eef_prev.inverse()
169-
T_eef_prev = T_eef.copy()
169+
T_palm = configuration.get_transform_frame_to_world(
170+
"leap_right/palm_lower", "body"
171+
)
172+
T = T_palm @ T_palm_prev.inverse()
173+
T_palm_prev = T_palm.copy()
170174

171175
for finger in fingers:
172176
mocap_id = model.body(f"{finger}_target").mocapid[0]

0 commit comments

Comments
 (0)