Skip to content

Commit 36ef08e

Browse files
authored
Merge pull request #125 from cpaxton/feature/smartmove-constraints
Debugging info + data collection
2 parents 30ffee0 + edbd117 commit 36ef08e

File tree

1 file changed

+51
-12
lines changed

1 file changed

+51
-12
lines changed

costar_robot/costar_robot_manager/src/costar_robot/costar_arm.py

Lines changed: 51 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -137,6 +137,7 @@ def __init__(self,
137137
self.plan_home_srv = self.make_service('PlanToHome',ServoToPose,self.plan_to_home_cb)
138138
self.smartmove = self.make_service('SmartMove',SmartMove,self.smart_move_cb)
139139
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)
140141
self.smartmove_release_srv = self.make_service('SmartRelease',SmartMove,self.smartmove_release_cb)
141142
self.smartmove_grasp_srv = self.make_service('SmartGrasp',SmartMove,self.smartmove_grasp_cb)
142143
self.smartmove_grasp_srv = self.make_service('SmartPlace',SmartMove,self.smartmove_place_cb)
@@ -155,6 +156,7 @@ def __init__(self,
155156

156157
self.status_pub = self.make_pub('DriverStatus',String,queue_size=1000)
157158
self.info_pub = self.make_pub('info',String,queue_size=1000)
159+
self.object_pub = self.make_pub('SmartMove/object',String,queue_size=1000)
158160
self.display_pub = self.make_pub('display_trajectory',DisplayTrajectory,queue_size=1000)
159161

160162
self.robot = URDF.from_parameter_server()
@@ -437,8 +439,9 @@ def send_trajectory(self,traj,stamp,acceleration=0.5,velocity=0.5,cartesian=Fals
437439
rospy.logerr("Function 'send_trajectory' not implemented for base class!")
438440
return "FAILURE -- running base class!"
439441

440-
def info(self, msg):
442+
def info(self, msg, object_name):
441443
self.info_pub.publish(data=msg)
444+
self.object_pub.publish(data=object_name)
442445

443446
'''
444447
Standard movement call.
@@ -514,16 +517,52 @@ def servo_to_home_cb(self,req):
514517
rospy.logerr('SIMPLE DRIVER -- Not in servo mode')
515518
return 'FAILURE -- not in servo mode'
516519

517-
'''
518-
Standard move call.
519-
Make a joint space move to a destination.
520-
'''
521520
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):
522556

523557
if self.driver_status == 'SERVO':
524558
# Check acceleration and velocity limits
525559
(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)
527566

528567
else:
529568
rospy.logerr('SIMPLE DRIVER -- Not in servo mode')
@@ -1006,17 +1045,17 @@ def smartmove_multipurpose_gripper(self,
10061045
if dist > 2 * backup_dist:
10071046
rospy.logwarn("Backoff failed for pose %i: distance was %f vs %f"%(sequence_number,dist,2*backup_dist))
10081047
continue
1009-
self.info("appoach_%s"%obj)
1048+
self.info("appoach_%s"%obj, obj)
10101049
msg = self.send_and_publish_planning_result(res,stamp,acceleration,velocity)
10111050
rospy.sleep(0.1)
10121051

10131052
if msg[0:7] == 'SUCCESS':
1014-
self.info("move_to_grasp_%s"%obj)
1053+
self.info("move_to_grasp_%s"%obj, obj)
10151054
msg = self.send_and_publish_planning_result(res2,stamp,acceleration,velocity)
10161055
rospy.sleep(0.1)
10171056

10181057
if msg[0:7] == 'SUCCESS':
1019-
self.info("take_%s"%obj)
1058+
self.info("take_%s"%obj, obj)
10201059
gripper_function(obj)
10211060

10221061
traj = res2.planned_trajectory.joint_trajectory
@@ -1030,7 +1069,7 @@ def smartmove_multipurpose_gripper(self,
10301069
traj.points[0].positions = self.q0
10311070
traj.points[-1].velocities = [0.]*len(self.q0)
10321071

1033-
self.info("backoff_from_%s"%obj)
1072+
self.info("backoff_from_%s"%obj, obj)
10341073
msg = self.send_and_publish_planning_result(res2,stamp,acceleration,velocity)
10351074
return msg
10361075
else:
@@ -1103,7 +1142,7 @@ def smartmove_release_cb(self, req):
11031142
stamp = self.acquire()
11041143
list_of_waypoints = self.query(req, True)
11051144
if len(list_of_waypoints) == 0:
1106-
return "FAILURE -- no suitable points found"
1145+
return "FAILURE -- no suitable waypoints found for release"
11071146
distance = req.backoff
11081147
return self.smartmove_release(stamp, list_of_waypoints, distance, req.vel, req.accel)
11091148

@@ -1114,7 +1153,7 @@ def smartmove_grasp_cb(self, req):
11141153
stamp = self.acquire()
11151154
list_of_waypoints = self.query(req, True)
11161155
if len(list_of_waypoints) == 0:
1117-
return "FAILURE -- no suitable points found"
1156+
return "FAILURE -- no suitable waypoints found for grasp"
11181157
distance = req.backoff
11191158
return self.smartmove_grasp(stamp, list_of_waypoints, distance, req.vel, req.accel)
11201159

0 commit comments

Comments
 (0)