Skip to content

Commit

Permalink
try fixing issue in hard reset
Browse files Browse the repository at this point in the history
  • Loading branch information
taochenshh committed Apr 13, 2022
1 parent 83e7cb0 commit 6a0650f
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 12 deletions.
36 changes: 25 additions & 11 deletions src/airobot/ee_tool/robotiq2f140_pybullet.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,16 +26,8 @@ class Robotiq2F140Pybullet(SimpleGripperPybullet):
def __init__(self, cfgs, pb_client):
super(Robotiq2F140Pybullet, self).__init__(cfgs=cfgs,
pb_client=pb_client)

def _setup_gripper(self):
"""
Setup the gripper, pass the robot info from the arm to the gripper.
Args:
robot_id (int): robot id in Pybullet.
jnt_to_id (dict): mapping from the joint name to joint id.
"""

def _create_constraint(self):
c_mimic = self._pb.createConstraint(
self.robot_id,
self.jnt_to_id['finger_joint'],
Expand Down Expand Up @@ -71,6 +63,16 @@ def _setup_gripper(self):
childFramePosition=child_pos)
self._pb.changeConstraint(c2, erp=0.8, maxForce=9999)

def _setup_gripper(self):
"""
Setup the gripper, pass the robot info from the arm to the gripper.
Args:
robot_id (int): robot id in Pybullet.
jnt_to_id (dict): mapping from the joint name to joint id.
"""
self._create_constraint()
passive_force = 0
for name in self.jnt_names:
if name == 'finger_joint':
Expand Down Expand Up @@ -153,7 +155,9 @@ def set_jpos(self, pos, wait=True, ignore_physics=False):

if ignore_physics:
self._zero_vel_mode()
self._hard_reset(mic_pos)
tgt_pos_mimic = self._mimic_gripper(tgt_pos)
self._hard_reset(tgt_pos_mimic)
self._create_constraint()
success = True
else:
self._pb.setJointMotorControl2(self.robot_id,
Expand Down Expand Up @@ -220,4 +224,14 @@ def get_jvel(self):
jnt_id = self.jnt_to_id[self.jnt_names[0]]
vel = self._pb.getJointState(self.robot_id, jnt_id)[1]
return vel

def _mimic_gripper(self, joint_val):
"""
Given the value for the first joint,
mimic the joint values for the rest joints.
"""
jnt_vals = [joint_val]
for i in range(1, len(self.jnt_names)):
jnt_vals.append(joint_val * self.cfgs.EETOOL.MIMIC_COEFF[i])
return jnt_vals

2 changes: 1 addition & 1 deletion src/airobot/ee_tool/simple_gripper_pybullet.py
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ def _zero_vel_mode(self):
forces=[10] * len(self.gripper_jnt_ids))

def _hard_reset(self, pos):
for i in range(len(self.gripper_jnt_ids)):
for i in range(min(len(self.gripper_jnt_ids), len(pos))):
self._pb.resetJointState(self.robot_id,
self.gripper_jnt_ids[i],
targetValue=pos[i],
Expand Down

0 comments on commit 6a0650f

Please sign in to comment.