14
14
15
15
# Initialize controller
16
16
ctrl = Controller ()
17
- MIN_JOINT_MOTION_FOR_HAND_OVER = 0.1
17
+ MIN_JOINT_MOTION_FOR_HAND_OVER = 0.05
18
18
# define state Idle
19
19
class Idle (smach .State ):
20
20
def __init__ (self ):
@@ -99,7 +99,7 @@ def __init__(self):
99
99
100
100
def execute (self , userdata ):
101
101
ctrl .set_camera_angles (ctrl .HOME_POS_CAMERA_02 )
102
- ctrl .set_arm_joint_angles (ctrl .HOME_POS_MANIPULATOR_02 )
102
+ ctrl .set_arm_joint_angles (ctrl .HOME_POS_MANIPULATOR_00 )
103
103
rospy .loginfo ('Executing state MoveHome2' )
104
104
return 'reached'
105
105
@@ -135,7 +135,7 @@ def execute(self, userdata):
135
135
## Make a different function with gripper pointing upwards and call it from here
136
136
rospy .loginfo ('Executing state IK2' )
137
137
success = ctrl .go_to_handover_pose (userdata .head_pose )
138
- rospy .sleep (8 )
138
+ rospy .sleep (3 )
139
139
if not success :
140
140
return 'noIK'
141
141
return 'foundIK'
@@ -161,7 +161,6 @@ def execute(self, userdata):
161
161
P ,I ,D = userdata .PID
162
162
for joint_num in userdata .joint_nums :
163
163
response = set_PID (joint_num , P , I , D )
164
- rospy .sleep (10 )
165
164
return 'changed'
166
165
except rospy .ServiceException as e :
167
166
rospy .logwarn ("Service call failed:{0}" .format (e ))
@@ -178,11 +177,12 @@ def execute(self, userdata):
178
177
while (True ):
179
178
joint_len = len (ctrl .history ['joint_feedback' ][0 ])
180
179
joint_sum = np .zeros (ctrl .history ['joint_feedback' ][0 ].shape )
181
- for joint_feedback in ctrl .history ['joint_feedback' ]:
182
- # pdb.set_trace()
180
+ for joint_feedback in list ( ctrl .history ['joint_feedback' ]) :
181
+ #pdb.set_trace()
183
182
joint_sum += joint_feedback - ctrl .current_target_state
184
183
avg_joint_sum = joint_sum / joint_len
185
- if (np .sum (avg_joint_sum ) > MIN_JOINT_MOTION_FOR_HAND_OVER ):
184
+ # print(joint_sum)
185
+ if (np .abs (np .sum (avg_joint_sum )) > MIN_JOINT_MOTION_FOR_HAND_OVER ):
186
186
ctrl .open_gripper ()
187
187
rospy .sleep (1 )
188
188
return 'opened'
@@ -195,7 +195,7 @@ def main():
195
195
# Create a SMACH state machine
196
196
sm = smach .StateMachine (outcomes = ['stop' ])
197
197
sm .userdata .tool_id = - 1
198
- sm .userdata .joint_nums = [1 , 6 ]
198
+ sm .userdata .joint_nums = [0 , 5 ]
199
199
sm .userdata .PID_Final = [0 ,0 ,0 ]
200
200
sm .userdata .PID_Initial = [640 ,5 ,50 ]
201
201
sis = smach_ros .IntrospectionServer ('server_name' , sm , '/SM_ROOT' )
0 commit comments