Skip to content

Commit 6a0650f

Browse files
committed
try fixing issue in hard reset
1 parent 83e7cb0 commit 6a0650f

File tree

2 files changed

+26
-12
lines changed

2 files changed

+26
-12
lines changed

src/airobot/ee_tool/robotiq2f140_pybullet.py

Lines changed: 25 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -26,16 +26,8 @@ class Robotiq2F140Pybullet(SimpleGripperPybullet):
2626
def __init__(self, cfgs, pb_client):
2727
super(Robotiq2F140Pybullet, self).__init__(cfgs=cfgs,
2828
pb_client=pb_client)
29-
30-
def _setup_gripper(self):
31-
"""
32-
Setup the gripper, pass the robot info from the arm to the gripper.
33-
34-
Args:
35-
robot_id (int): robot id in Pybullet.
36-
jnt_to_id (dict): mapping from the joint name to joint id.
37-
38-
"""
29+
30+
def _create_constraint(self):
3931
c_mimic = self._pb.createConstraint(
4032
self.robot_id,
4133
self.jnt_to_id['finger_joint'],
@@ -71,6 +63,16 @@ def _setup_gripper(self):
7163
childFramePosition=child_pos)
7264
self._pb.changeConstraint(c2, erp=0.8, maxForce=9999)
7365

66+
def _setup_gripper(self):
67+
"""
68+
Setup the gripper, pass the robot info from the arm to the gripper.
69+
70+
Args:
71+
robot_id (int): robot id in Pybullet.
72+
jnt_to_id (dict): mapping from the joint name to joint id.
73+
74+
"""
75+
self._create_constraint()
7476
passive_force = 0
7577
for name in self.jnt_names:
7678
if name == 'finger_joint':
@@ -153,7 +155,9 @@ def set_jpos(self, pos, wait=True, ignore_physics=False):
153155

154156
if ignore_physics:
155157
self._zero_vel_mode()
156-
self._hard_reset(mic_pos)
158+
tgt_pos_mimic = self._mimic_gripper(tgt_pos)
159+
self._hard_reset(tgt_pos_mimic)
160+
self._create_constraint()
157161
success = True
158162
else:
159163
self._pb.setJointMotorControl2(self.robot_id,
@@ -220,4 +224,14 @@ def get_jvel(self):
220224
jnt_id = self.jnt_to_id[self.jnt_names[0]]
221225
vel = self._pb.getJointState(self.robot_id, jnt_id)[1]
222226
return vel
227+
228+
def _mimic_gripper(self, joint_val):
229+
"""
230+
Given the value for the first joint,
231+
mimic the joint values for the rest joints.
232+
"""
233+
jnt_vals = [joint_val]
234+
for i in range(1, len(self.jnt_names)):
235+
jnt_vals.append(joint_val * self.cfgs.EETOOL.MIMIC_COEFF[i])
236+
return jnt_vals
223237

src/airobot/ee_tool/simple_gripper_pybullet.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -179,7 +179,7 @@ def _zero_vel_mode(self):
179179
forces=[10] * len(self.gripper_jnt_ids))
180180

181181
def _hard_reset(self, pos):
182-
for i in range(len(self.gripper_jnt_ids)):
182+
for i in range(min(len(self.gripper_jnt_ids), len(pos))):
183183
self._pb.resetJointState(self.robot_id,
184184
self.gripper_jnt_ids[i],
185185
targetValue=pos[i],

0 commit comments

Comments
 (0)