35
35
import numpy as np
36
36
37
37
import bezier
38
+ import minjerk
38
39
39
40
import rospy
40
41
59
60
60
61
class JointTrajectoryActionServer (object ):
61
62
def __init__ (self , limb , reconfig_server , rate = 100.0 ,
62
- mode = 'position_w_id' ):
63
+ mode = 'position_w_id' , interpolation = 'bezier' ):
63
64
self ._dyn = reconfig_server
64
65
self ._ns = 'robot/limb/' + limb
65
66
self ._fjt_ns = self ._ns + '/follow_joint_trajectory'
@@ -72,6 +73,7 @@ def __init__(self, limb, reconfig_server, rate=100.0,
72
73
self ._limb = baxter_interface .Limb (limb )
73
74
self ._enable = baxter_interface .RobotEnable ()
74
75
self ._name = limb
76
+ self ._interpolation = interpolation
75
77
self ._cuff = baxter_interface .DigitalIO ('%s_lower_cuff' % (limb ,))
76
78
self ._cuff .state_changed .connect (self ._cuff_cb )
77
79
# Verify joint control mode
@@ -332,6 +334,47 @@ def _compute_bezier_coeff(self, joint_names, trajectory_points, dimensions_dict)
332
334
b_matrix [jnt , :, :, :] = bezier .bezier_coefficients (traj_array , d_pts )
333
335
return b_matrix
334
336
337
+ def _get_minjerk_point (self , m_matrix , idx , t , cmd_time , dimensions_dict ):
338
+ pnt = JointTrajectoryPoint ()
339
+ pnt .time_from_start = rospy .Duration (cmd_time )
340
+ num_joints = m_matrix .shape [0 ]
341
+ pnt .positions = [0.0 ] * num_joints
342
+ if dimensions_dict ['velocities' ]:
343
+ pnt .velocities = [0.0 ] * num_joints
344
+ if dimensions_dict ['accelerations' ]:
345
+ pnt .accelerations = [0.0 ] * num_joints
346
+ for jnt in range (num_joints ):
347
+ m_point = minjerk .minjerk_point (m_matrix [jnt , :, :, :], idx , t )
348
+ # Positions at specified time
349
+ pnt .positions [jnt ] = m_point [0 ]
350
+ # Velocities at specified time
351
+ if dimensions_dict ['velocities' ]:
352
+ pnt .velocities [jnt ] = m_point [1 ]
353
+ # Accelerations at specified time
354
+ if dimensions_dict ['accelerations' ]:
355
+ pnt .accelerations [jnt ] = m_point [- 1 ]
356
+ return pnt
357
+
358
+ def _compute_minjerk_coeff (self , joint_names , trajectory_points , point_duration , dimensions_dict ):
359
+ # Compute Full Minimum Jerk Curve
360
+ num_joints = len (joint_names )
361
+ num_traj_pts = len (trajectory_points )
362
+ num_traj_dim = sum (dimensions_dict .values ())
363
+ num_m_values = len (['a0' , 'a1' , 'a2' , 'a3' , 'a4' , 'a5' , 'tm' ])
364
+ m_matrix = np .zeros (shape = (num_joints , num_traj_dim , num_traj_pts - 1 , num_m_values ))
365
+ for jnt in xrange (num_joints ):
366
+ traj_array = np .zeros (shape = (len (trajectory_points ), num_traj_dim ))
367
+ for idx , point in enumerate (trajectory_points ):
368
+ current_point = list ()
369
+ current_point .append (point .positions [jnt ])
370
+ if dimensions_dict ['velocities' ]:
371
+ current_point .append (point .velocities [jnt ])
372
+ if dimensions_dict ['accelerations' ]:
373
+ current_point .append (point .accelerations [jnt ])
374
+ traj_array [idx , :] = current_point
375
+ m_matrix [jnt , :, :, :] = minjerk .minjerk_coefficients (traj_array , point_duration )
376
+ return m_matrix
377
+
335
378
def _determine_dimensions (self , trajectory_points ):
336
379
# Determine dimensions supplied
337
380
position_flag = True
@@ -385,15 +428,24 @@ def _on_trajectory_action(self, goal):
385
428
if dimensions_dict ['accelerations' ]:
386
429
trajectory_points [- 1 ].accelerations = [0.0 ] * len (joint_names )
387
430
388
- # Compute Full Bezier Curve Coefficients for all 7 joints
389
431
pnt_times = [pnt .time_from_start .to_sec () for pnt in trajectory_points ]
390
432
try :
391
- b_matrix = self ._compute_bezier_coeff (joint_names ,
392
- trajectory_points ,
393
- dimensions_dict )
433
+ if self ._interpolation == 'minjerk' :
434
+ # Compute Full MinJerk Curve Coefficients for all 7 joints
435
+ point_duration = [pnt_times [i + 1 ] - pnt_times [i ] for i in range (len (pnt_times )- 1 )]
436
+ m_matrix = self ._compute_minjerk_coeff (joint_names ,
437
+ trajectory_points ,
438
+ point_duration ,
439
+ dimensions_dict )
440
+ else :
441
+ # Compute Full Bezier Curve Coefficients for all 7 joints
442
+ b_matrix = self ._compute_bezier_coeff (joint_names ,
443
+ trajectory_points ,
444
+ dimensions_dict )
394
445
except Exception as ex :
395
- rospy .logerr (("{0}: Failed to compute a Bezier trajectory for {1}"
396
- " arm with error \" {2}: {3}\" " ).format (
446
+ rospy .logerr (("{0}: Failed to compute a {1} trajectory for {2}"
447
+ " arm with error \" {3}: {4}\" " ).format (
448
+ self ._interpolation ,
397
449
self ._action_name ,
398
450
self ._name ,
399
451
type (ex ).__name__ , ex ))
@@ -429,9 +481,14 @@ def _on_trajectory_action(self, goal):
429
481
cmd_time = 0
430
482
t = 0
431
483
432
- point = self ._get_bezier_point (b_matrix , idx ,
433
- t , cmd_time ,
434
- dimensions_dict )
484
+ if self ._interpolation == 'minjerk' :
485
+ point = self ._get_minjerk_point (m_matrix , idx ,
486
+ t , cmd_time ,
487
+ dimensions_dict )
488
+ else :
489
+ point = self ._get_bezier_point (b_matrix , idx ,
490
+ t , cmd_time ,
491
+ dimensions_dict )
435
492
436
493
# Command Joint Position, Velocity, Acceleration
437
494
command_executed = self ._command_joints (joint_names , point , start_time , dimensions_dict )
0 commit comments