@@ -70,6 +70,7 @@ def __init__(self, limb, reconfig_server, rate=100.0,
70
70
auto_start = False )
71
71
self ._action_name = rospy .get_name ()
72
72
self ._limb = baxter_interface .Limb (limb )
73
+ self ._enable = baxter_interface .RobotEnable ()
73
74
self ._name = limb
74
75
self ._cuff = baxter_interface .DigitalIO ('%s_lower_cuff' % (limb ,))
75
76
self ._cuff .state_changed .connect (self ._cuff_cb )
@@ -120,6 +121,9 @@ def __init__(self, limb, reconfig_server, rate=100.0,
120
121
tcp_nodelay = True ,
121
122
queue_size = 1 )
122
123
124
+ def robot_is_enabled (self ):
125
+ return self ._enable .state ().enabled
126
+
123
127
def clean_shutdown (self ):
124
128
self ._alive = False
125
129
self ._limb .exit_control_mode ()
@@ -225,7 +229,8 @@ def _command_stop(self, joint_names, joint_angles, start_time, dimensions_dict):
225
229
if self ._mode == 'velocity' :
226
230
velocities = [0.0 ] * len (joint_names )
227
231
cmd = dict (zip (joint_names , velocities ))
228
- while (not self ._server .is_new_goal_available () and self ._alive ):
232
+ while (not self ._server .is_new_goal_available () and self ._alive
233
+ and self .robot_is_enabled ()):
229
234
self ._limb .set_joint_velocities (cmd )
230
235
if self ._cuff_state :
231
236
self ._limb .exit_control_mode ()
@@ -240,7 +245,8 @@ def _command_stop(self, joint_names, joint_angles, start_time, dimensions_dict):
240
245
pnt .velocities = [0.0 ] * len (joint_names )
241
246
if dimensions_dict ['accelerations' ]:
242
247
pnt .accelerations = [0.0 ] * len (joint_names )
243
- while (not self ._server .is_new_goal_available () and self ._alive ):
248
+ while (not self ._server .is_new_goal_available () and self ._alive
249
+ and self .robot_is_enabled ()):
244
250
self ._limb .set_joint_positions (joint_angles , raw = raw_pos_mode )
245
251
# zero inverse dynamics feedforward command
246
252
if self ._mode == 'position_w_id' :
@@ -253,16 +259,16 @@ def _command_stop(self, joint_names, joint_angles, start_time, dimensions_dict):
253
259
rospy .sleep (1.0 / self ._control_rate )
254
260
255
261
def _command_joints (self , joint_names , point , start_time , dimensions_dict ):
256
- if self ._server .is_preempt_requested ():
262
+ if self ._server .is_preempt_requested () or not self . robot_is_enabled () :
257
263
rospy .loginfo ("%s: Trajectory Preempted" % (self ._action_name ,))
258
264
self ._server .set_preempted ()
259
265
self ._command_stop (joint_names , self ._limb .joint_angles (), start_time , dimensions_dict )
260
266
return False
261
267
velocities = []
262
268
deltas = self ._get_current_error (joint_names , point .positions )
263
269
for delta in deltas :
264
- if (math .fabs (delta [1 ]) >= self ._path_thresh [delta [0 ]]
265
- and self ._path_thresh [delta [0 ]] >= 0.0 ):
270
+ if (( math .fabs (delta [1 ]) >= self ._path_thresh [delta [0 ]]
271
+ and self ._path_thresh [delta [0 ]] >= 0.0 )) or not self . robot_is_enabled () :
266
272
rospy .logerr ("%s: Exceeded Error Threshold on %s: %s" %
267
273
(self ._action_name , delta [0 ], str (delta [1 ]),))
268
274
self ._result .error_code = self ._result .PATH_TOLERANCE_VIOLATED
@@ -406,7 +412,8 @@ def _on_trajectory_action(self, goal):
406
412
# Keep track of current indices for spline segment generation
407
413
now_from_start = rospy .get_time () - start_time
408
414
end_time = trajectory_points [- 1 ].time_from_start .to_sec ()
409
- while (now_from_start < end_time and not rospy .is_shutdown ()):
415
+ while (now_from_start < end_time and not rospy .is_shutdown () and
416
+ self .robot_is_enabled ()):
410
417
#Acquire Mutex
411
418
now = rospy .get_time ()
412
419
now_from_start = now - start_time
@@ -451,7 +458,7 @@ def check_goal_state():
451
458
return True
452
459
453
460
while (now_from_start < (last_time + self ._goal_time )
454
- and not rospy .is_shutdown ()):
461
+ and not rospy .is_shutdown () and self . robot_is_enabled () ):
455
462
if not self ._command_joints (joint_names , last , start_time , dimensions_dict ):
456
463
return
457
464
now_from_start = rospy .get_time () - start_time
0 commit comments