@@ -137,6 +137,7 @@ def __init__(self,
137
137
self .plan_home_srv = self .make_service ('PlanToHome' ,ServoToPose ,self .plan_to_home_cb )
138
138
self .smartmove = self .make_service ('SmartMove' ,SmartMove ,self .smart_move_cb )
139
139
self .js_servo = self .make_service ('ServoToJointState' ,ServoToJointState ,self .servo_to_joints_cb )
140
+ self .js_plan = self .make_service ('PlanToJointState' ,ServoToJointState ,self .plan_to_joints_cb )
140
141
self .smartmove_release_srv = self .make_service ('SmartRelease' ,SmartMove ,self .smartmove_release_cb )
141
142
self .smartmove_grasp_srv = self .make_service ('SmartGrasp' ,SmartMove ,self .smartmove_grasp_cb )
142
143
self .smartmove_grasp_srv = self .make_service ('SmartPlace' ,SmartMove ,self .smartmove_place_cb )
@@ -155,6 +156,7 @@ def __init__(self,
155
156
156
157
self .status_pub = self .make_pub ('DriverStatus' ,String ,queue_size = 1000 )
157
158
self .info_pub = self .make_pub ('info' ,String ,queue_size = 1000 )
159
+ self .object_pub = self .make_pub ('SmartMove/object' ,String ,queue_size = 1000 )
158
160
self .display_pub = self .make_pub ('display_trajectory' ,DisplayTrajectory ,queue_size = 1000 )
159
161
160
162
self .robot = URDF .from_parameter_server ()
@@ -437,8 +439,9 @@ def send_trajectory(self,traj,stamp,acceleration=0.5,velocity=0.5,cartesian=Fals
437
439
rospy .logerr ("Function 'send_trajectory' not implemented for base class!" )
438
440
return "FAILURE -- running base class!"
439
441
440
- def info (self , msg ):
442
+ def info (self , msg , object_name ):
441
443
self .info_pub .publish (data = msg )
444
+ self .object_pub .publish (data = object_name )
442
445
443
446
'''
444
447
Standard movement call.
@@ -514,16 +517,52 @@ def servo_to_home_cb(self,req):
514
517
rospy .logerr ('SIMPLE DRIVER -- Not in servo mode' )
515
518
return 'FAILURE -- not in servo mode'
516
519
517
- '''
518
- Standard move call.
519
- Make a joint space move to a destination.
520
- '''
521
520
def servo_to_joints_cb (self ,req ):
521
+ if self .driver_status == 'SERVO' :
522
+
523
+ # Check acceleration and velocity limits
524
+ (acceleration , velocity ) = self .check_req_speed_params (req )
525
+
526
+ stamp = self .acquire ()
527
+
528
+ # inverse kinematics
529
+ traj = self .planner .getJointMove (req .target .position ,
530
+ self .q0 ,
531
+ self .base_steps ,
532
+ self .steps_per_meter ,
533
+ self .steps_per_radians ,
534
+ time_multiplier = (1. / velocity ),
535
+ percent_acc = acceleration ,
536
+ use_joint_move = True ,
537
+ table_frame = self .table_pose )
538
+
539
+ # Send command
540
+ if len (traj .points ) > 0 :
541
+ if stamp is not None :
542
+ rospy .logwarn ("Robot moving to " + str (traj .points [- 1 ].positions ))
543
+ res = self .send_trajectory (traj ,stamp ,acceleration ,velocity ,cartesian = False )
544
+ self .release ()
545
+ else :
546
+ res = 'FAILURE -- could not preempt current arm control.'
547
+ return res
548
+ else :
549
+ rospy .logerr ('SIMPLE DRIVER -- IK failed' )
550
+ return 'FAILURE -- no trajectory points'
551
+ else :
552
+ rospy .logerr ('SIMPLE DRIVER -- Not in servo mode' )
553
+ return 'FAILURE -- not in servo mode'
554
+
555
+ def plan_to_joints_cb (self ,req ):
522
556
523
557
if self .driver_status == 'SERVO' :
524
558
# Check acceleration and velocity limits
525
559
(acceleration , velocity ) = self .check_req_speed_params (req )
526
- return 'FAILURE -- not yet implemented!'
560
+ stamp = self .acquire ()
561
+
562
+ # Send command
563
+ pt = JointTrajectoryPoint ()
564
+ (code ,res ) = self .planner .getPlan (q_goal = req .target .position ,q = self .q0 )
565
+ return self .send_and_publish_planning_result (res ,stamp ,acceleration ,velocity )
527
566
528
567
else :
529
568
rospy .logerr ('SIMPLE DRIVER -- Not in servo mode' )
@@ -1006,17 +1045,17 @@ def smartmove_multipurpose_gripper(self,
1006
1045
if dist > 2 * backup_dist :
1007
1046
rospy .logwarn ("Backoff failed for pose %i: distance was %f vs %f" % (sequence_number ,dist ,2 * backup_dist ))
1008
1047
continue
1009
- self .info ("appoach_%s" % obj )
1048
+ self .info ("appoach_%s" % obj , obj )
1010
1049
msg = self .send_and_publish_planning_result (res ,stamp ,acceleration ,velocity )
1011
1050
rospy .sleep (0.1 )
1012
1051
1013
1052
if msg [0 :7 ] == 'SUCCESS' :
1014
- self .info ("move_to_grasp_%s" % obj )
1053
+ self .info ("move_to_grasp_%s" % obj , obj )
1015
1054
msg = self .send_and_publish_planning_result (res2 ,stamp ,acceleration ,velocity )
1016
1055
rospy .sleep (0.1 )
1017
1056
1018
1057
if msg [0 :7 ] == 'SUCCESS' :
1019
- self .info ("take_%s" % obj )
1058
+ self .info ("take_%s" % obj , obj )
1020
1059
gripper_function (obj )
1021
1060
1022
1061
traj = res2 .planned_trajectory .joint_trajectory
@@ -1030,7 +1069,7 @@ def smartmove_multipurpose_gripper(self,
1030
1069
traj .points [0 ].positions = self .q0
1031
1070
traj .points [- 1 ].velocities = [0. ]* len (self .q0 )
1032
1071
1033
- self .info ("backoff_from_%s" % obj )
1072
+ self .info ("backoff_from_%s" % obj , obj )
1034
1073
msg = self .send_and_publish_planning_result (res2 ,stamp ,acceleration ,velocity )
1035
1074
return msg
1036
1075
else :
@@ -1103,7 +1142,7 @@ def smartmove_release_cb(self, req):
1103
1142
stamp = self .acquire ()
1104
1143
list_of_waypoints = self .query (req , True )
1105
1144
if len (list_of_waypoints ) == 0 :
1106
- return "FAILURE -- no suitable points found"
1145
+ return "FAILURE -- no suitable waypoints found for release "
1107
1146
distance = req .backoff
1108
1147
return self .smartmove_release (stamp , list_of_waypoints , distance , req .vel , req .accel )
1109
1148
@@ -1114,7 +1153,7 @@ def smartmove_grasp_cb(self, req):
1114
1153
stamp = self .acquire ()
1115
1154
list_of_waypoints = self .query (req , True )
1116
1155
if len (list_of_waypoints ) == 0 :
1117
- return "FAILURE -- no suitable points found"
1156
+ return "FAILURE -- no suitable waypoints found for grasp "
1118
1157
distance = req .backoff
1119
1158
return self .smartmove_grasp (stamp , list_of_waypoints , distance , req .vel , req .accel )
1120
1159
0 commit comments