Open gripper after each run
This commit is contained in:
parent
1c3764f785
commit
571b382654
@ -40,11 +40,10 @@ class HwNode:
|
|||||||
return SeedResponse()
|
return SeedResponse()
|
||||||
|
|
||||||
def reset(self, req):
|
def reset(self, req):
|
||||||
self.gripper.move(0.04)
|
|
||||||
|
|
||||||
# Move to the initial configuration
|
# Move to the initial configuration
|
||||||
self.switch_to_joint_trajectory_controller()
|
self.switch_to_joint_trajectory_controller()
|
||||||
self.moveit.goto(self.scene_config["q0"])
|
self.moveit.goto(self.scene_config["q0"])
|
||||||
|
self.gripper.move(0.04)
|
||||||
|
|
||||||
# Construct bounding box
|
# Construct bounding box
|
||||||
bbox_min = self.T_base_roi.apply(self.scene_config["target"]["min"])
|
bbox_min = self.T_base_roi.apply(self.scene_config["target"]["min"])
|
||||||
|
@ -87,6 +87,7 @@ class GraspController:
|
|||||||
res = self.execute_grasp(grasp)
|
res = self.execute_grasp(grasp)
|
||||||
else:
|
else:
|
||||||
res = "aborted"
|
res = "aborted"
|
||||||
|
self.gripper.move(0.04)
|
||||||
return self.collect_info(res)
|
return self.collect_info(res)
|
||||||
|
|
||||||
def reset(self):
|
def reset(self):
|
||||||
|
Loading…
x
Reference in New Issue
Block a user