~shadowrobot/sr-manipulation/trunk

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
#!/usr/bin/env python
#
# Copyright 2011 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
# Software Foundation, either version 2 of the License, or (at your option)
# any later version.
#
# This program is distributed in the hope that it will be useful, but WITHOUT
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
# FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
# more details.
#
# You should have received a copy of the GNU General Public License along
# with this program.  If not, see <http://www.gnu.org/licenses/>.
#

import roslib; roslib.load_manifest("sr_pick_and_place")
import rospy

from arm_navigation_msgs.srv import GetMotionPlan, GetMotionPlanRequest, GetMotionPlanResponse, FilterJointTrajectoryWithConstraints, FilterJointTrajectoryWithConstraintsRequest
from arm_navigation_msgs.srv import SetPlanningSceneDiff, SetPlanningSceneDiffRequest
from arm_navigation_msgs.msg import MotionPlanRequest, PositionConstraint, OrientationConstraint, DisplayTrajectory, Constraints, JointConstraint, JointLimits, RobotState, AttachedCollisionObject, CollisionObjectOperation, Shape
from interpolated_ik_motion_planner.srv import SetInterpolatedIKMotionPlanParams
#import interpolated_ik_motion_planner.ik_utilities as ik_utilities
from kinematics_msgs.srv import GetConstraintAwarePositionIK
from kinematics_msgs.msg import PositionIKRequest
from geometry_msgs.msg import PoseStamped, Pose
from trajectory_msgs.msg import JointTrajectory
from sr_utilities.srv import getJointState

import time
import math

ARM_NAMES = ['ShoulderJRotate', 'ShoulderJSwing', 'ElbowJSwing', 'ElbowJRotate', "WRJ1", "WRJ2"]
ARM_IK_SEED = [-0.0011556513918362654, 0.33071140061761284, 1.9152039367468952, 0.008440334101951663, 0.0, 0.0]

class Planification(object):
    """
    """

    def __init__(self, ):
        """
        """
        rospy.loginfo("Waiting for services /ompl_planning/plan_kinematic_path, /environment_server/set_planning_scene_diff, /shadow_right_arm_kinematics/get_constraint_aware_ik ...")

        rospy.wait_for_service("/ompl_planning/plan_kinematic_path")
        rospy.wait_for_service("/environment_server/set_planning_scene_diff")
        rospy.wait_for_service("/shadow_right_arm_kinematics/get_constraint_aware_ik")
        rospy.wait_for_service("/r_interpolated_ik_motion_plan_set_params")
        rospy.wait_for_service("/r_interpolated_ik_motion_plan")
        rospy.wait_for_service("/trajectory_filter_server/filter_trajectory_with_constraints")
        rospy.wait_for_service("/getJointState")
        rospy.loginfo("  OK services found")

        self.set_planning_scene_diff_ = rospy.ServiceProxy("/environment_server/set_planning_scene_diff", SetPlanningSceneDiff)
        self.planifier_ = rospy.ServiceProxy('/ompl_planning/plan_kinematic_path', GetMotionPlan)
        self.constraint_aware_ik_ = rospy.ServiceProxy("/shadow_right_arm_kinematics/get_constraint_aware_ik", GetConstraintAwarePositionIK)
        self.interpolated_ik_params_srv = rospy.ServiceProxy('/r_interpolated_ik_motion_plan_set_params', SetInterpolatedIKMotionPlanParams)
        self.interpolated_ik_srv = rospy.ServiceProxy('/r_interpolated_ik_motion_plan', GetMotionPlan)
        self.trajectory_filter_ = rospy.ServiceProxy("/trajectory_filter_server/filter_trajectory_with_constraints", FilterJointTrajectoryWithConstraints)
        self.get_joint_state_ = rospy.ServiceProxy("/getJointState", getJointState) # TODO use another getJointstateProvided by env Server
         
        #self.ik_utils = ik_utilities.IKUtilities('right',None,0) # do not wait for service this is not needed for us

        #self.standard_ik_ = rospy.ServiceProxy("/shadow_right_arm_kinematics/get_ik", GetPositionIK)


    def plan_arm_motion(self, arm_name, planner, palm_target_pose, attached_object=[], hand_target_posture=[]):
        """Plan motion for the palm, eventually virtually setting the hand in the pre-grasp posture to manage grasping in small spaces
        """
        goal = PoseStamped()
        goal.header.frame_id = "world"
        
        goal.pose=palm_target_pose.pose
    
        #goal.pose.position.x = 0.470
        #goal.pose.position.y = -0.166
        #goal.pose.position.z = 1.665

        #goal.pose.orientation.x = 0.375
        #goal.pose.orientation.y = 0.155
        #goal.pose.orientation.z = 0.844
        #goal.pose.orientation.w = 0.351
        
        if(planner=="cartesianspace"):
            result=self.plan_motion_cartesian_( arm_name, goal )
        else:
            result=self.plan_motion_joint_state_( arm_name, goal , attached_object )
        
        return result

    def plan_motion_joint_state_(self, arm_name, goal_pose, attached_object_name=[], link_name = "palm"):
        self.reset_planning_scene_()
        if(attached_object_name):
            print "an object is attached"
            self.set_planning_scene_(attached_object_name)

        motion_plan_res= GetMotionPlanResponse()
        
        #first get the ik for the pose we want to go to
        ik_solution = None
        try:
            req = PositionIKRequest()
            req.ik_link_name = link_name
            req.pose_stamped = goal_pose
            req.ik_seed_state.joint_state.name = ARM_NAMES
            req.ik_seed_state.joint_state.position = ARM_IK_SEED
            ik_solution = self.constraint_aware_ik_.call( req, Constraints(), rospy.Duration(5.0) )
        except rospy.ServiceException, e:
            rospy.logerr( "Failed to compute IK "+str(e) )
            motion_plan_res.error_code.val = motion_plan_res.error_code.NO_IK_SOLUTION
            return motion_plan_res

        if ik_solution.error_code.val != ik_solution.error_code.SUCCESS:
            rospy.logerr("couldn't find an ik solution to go to: " + str(goal_pose))
            motion_plan_res.error_code.val = ik_solution.error_code.val
            return motion_plan_res

        #motion_plan_res = None
        #try to plan the motion to the target joint_state
        try:
            motion_plan_request = MotionPlanRequest()

            motion_plan_request.group_name = arm_name #"right_arm"
            motion_plan_request.num_planning_attempts = 1
            motion_plan_request.planner_id = ""
            motion_plan_request.allowed_planning_time = rospy.Duration(5.0)

            motion_plan_request.expected_path_duration = rospy.Duration(5.0)
            motion_plan_request.expected_path_dt = rospy.Duration(0.5)

            # set joint_constraints
            for target, name in zip(ik_solution.solution.joint_state.position, ik_solution.solution.joint_state.name):
                joint_constraint = JointConstraint()
                joint_constraint.joint_name = name
                joint_constraint.position = target
                joint_constraint.tolerance_below = 0.1
                joint_constraint.tolerance_above = 0.1

                motion_plan_request.goal_constraints.joint_constraints.append(joint_constraint)

            # start the planner
            motion_plan_res = self.planifier_( motion_plan_request )

            if motion_plan_res.error_code.val != motion_plan_res.error_code.SUCCESS:
                rospy.logerr("The planning failed: " + str(motion_plan_res.error_code.val))
            else:
                # compute velocity and appropriate times
                (times, vels) = self.trajectory_times_and_vels(motion_plan_res.trajectory, [.05]*6, [.1]*6)
                #print times
                #print vels
                for i in range(len(motion_plan_res.trajectory.joint_trajectory.points)):
                    motion_plan_res.trajectory.joint_trajectory.points[i].velocities = vels[i]
                    motion_plan_res.trajectory.joint_trajectory.points[i].time_from_start = rospy.Duration(times[i])
                #print motion_plan_res.trajectory.joint_trajectory
        except rospy.ServiceException, e:
            rospy.logerr( "Failed to plan "+str(e) )
            motion_plan_res.error_code.val = motion_plan_res.error_code.PLANNING_FAILED
        
        filtered_traj = self.filter_traj_(motion_plan_request, motion_plan_res)
        motion_plan_res.trajectory.joint_trajectory = filtered_traj
        
        return motion_plan_res

    def plan_motion_cartesian_(self, arm_name, goal_pose, link_name="palm"):
        self.reset_planning_scene_()

        motion_plan_res = None
        try:
            motion_plan_request = MotionPlanRequest()

            motion_plan_request.group_name = "right_arm_cartesian"
            motion_plan_request.num_planning_attempts = 1
            motion_plan_request.planner_id = ""
            motion_plan_request.allowed_planning_time = rospy.Duration(120.0)

            position_constraint = PositionConstraint()
            position_constraint.header.stamp = rospy.Time.now()
            position_constraint.header.frame_id = goal_pose.header.frame_id
            position_constraint.link_name = link_name
            position_constraint.position = goal_pose.pose.position
            position_constraint.constraint_region_shape.type = Shape.BOX
            position_constraint.constraint_region_shape.dimensions.append(0.1)
            position_constraint.constraint_region_shape.dimensions.append(0.1)
            position_constraint.constraint_region_shape.dimensions.append(0.1)
            position_constraint.weight = 1.0
            #position_constraint.constraint_region_orientation.x = 0.307
            #position_constraint.constraint_region_orientation.y = 0.127
            #position_constraint.constraint_region_orientation.z = 0.871
            #position_constraint.constraint_region_orientation.w = 0.362
            position_constraint.constraint_region_orientation.w = 1.0
            motion_plan_request.goal_constraints.position_constraints.append(position_constraint)

            orientation_constraint = OrientationConstraint()
            orientation_constraint.header.stamp = rospy.Time.now()
            orientation_constraint.header.frame_id = goal_pose.header.frame_id
            orientation_constraint.link_name = link_name

            orientation_constraint.orientation.x = 0.351
            orientation_constraint.orientation.y = 0.155
            orientation_constraint.orientation.z = 0.844
            orientation_constraint.orientation.w = 0.375

            #orientation_constraint.orientation.x = 0.454
            #orientation_constraint.orientation.y = 0.665
            #orientation_constraint.orientation.z = 0.499
            #orientation_constraint.orientation.w = 0.320

            orientation_constraint.absolute_roll_tolerance = 1.5
            orientation_constraint.absolute_pitch_tolerance = 1.5
            orientation_constraint.absolute_yaw_tolerance = 1.5
            orientation_constraint.weight = 0.5
            motion_plan_request.goal_constraints.orientation_constraints.append(orientation_constraint)

            motion_plan_res = self.planifier_( motion_plan_request )

            if motion_plan_res.error_code.val == motion_plan_res.error_code.SUCCESS:
                self.display_traj_( motion_plan_res )
            else:
                rospy.logerr("The planning failed: " + str(motion_plan_res.error_code.val))

        except rospy.ServiceException, e:
            rospy.logerr( "Failed to plan "+str(e) )
            return False

    def filter_traj_(self, motion_plan_req, motion_plan_res):
        try:
            req = FilterJointTrajectoryWithConstraintsRequest()
            req.group_name="right_arm"
            for name in ARM_NAMES:
                limit = JointLimits()
                limit.joint_name = name
                limit.min_position = -1.5
                limit.max_position = 1.5
                limit.has_velocity_limits = True
                limit.max_velocity = 0.05
                limit.has_acceleration_limits = True
                limit.max_acceleration = 0.1
                req.limits.append(limit)

            req.trajectory = motion_plan_res.trajectory.joint_trajectory
            req.goal_constraints=motion_plan_req.goal_constraints
            req.path_constraints=motion_plan_req.path_constraints
            req.allowed_time = rospy.Duration.from_sec( 5.0 )
            res = self.get_joint_state_.call()
            req.start_state.joint_state = res.joint_state

            res = self.trajectory_filter_.call( req )
        except rospy.ServiceException, e:
            rospy.logerr("Failed to filter "+str(e))
            return motion_plan_res.trajectory

        return res.trajectory

    def get_interpolated_ik_motion_plan(self, start_pose, target_pose, collision_check=False,
                                        steps_before_abort=1, num_steps=0,
                                        frame='shadowarm_base', max_joint_vels=[0.1]*6, max_joint_accs=[0.3]*6):
                                        
        ik_motion_plan_res = self.interpolated_ik_params_srv(num_steps,
                                              math.pi/7.0,
                                              1,
                                              steps_before_abort,
                                              0.02,
                                              0.1,
                                              collision_check,
                                              1, #start from end
                                              max_joint_vels,
                                              max_joint_accs)
                                             

        self.reset_planning_scene_()
        ik_motion_plan_req = GetMotionPlanRequest()
        ik_motion_plan_req.motion_plan_request.start_state.joint_state.name = ARM_NAMES
        
        #joint_state_res = self.get_joint_state_.call()
        #start_angles = res.joint_state.positions # one cannot use this directly it contains not only arm but also fingers            
        ik_motion_plan_req.motion_plan_request.start_state.joint_state.position = [0.3]*6 #start_angles
        ik_motion_plan_req.motion_plan_request.start_state.multi_dof_joint_state.poses = [start_pose.pose]
        ik_motion_plan_req.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids = ["palm"]
        ik_motion_plan_req.motion_plan_request.start_state.multi_dof_joint_state.frame_ids = [start_pose.header.frame_id]
        
        pos_constraint = PositionConstraint()
        pos_constraint.position = target_pose.pose.position
        pos_constraint.header.frame_id = target_pose.header.frame_id
        ik_motion_plan_req.motion_plan_request.goal_constraints.position_constraints = [pos_constraint]
        
        orient_constraint = OrientationConstraint()
        orient_constraint.orientation = target_pose.pose.orientation
        orient_constraint.header.frame_id = target_pose.header.frame_id
        ik_motion_plan_req.motion_plan_request.goal_constraints.orientation_constraints = [orient_constraint]
        
        #if ordered_collision_operations is not None:
        #    ik_motion_plan_req.motion_plan_request.ordered_collision_operations = ordered_collision_operations
        #rospy.logerr("ik req")
        #print ik_motion_plan_req
        ik_motion_plan_res = self.interpolated_ik_srv(ik_motion_plan_req)
        return ik_motion_plan_res
      
    def trajectory_times_and_vels(self, traj, max_joint_vels = [.2]*6, max_joint_accs = [.5]*6):

        #min time for each segment
        min_segment_time = .01
        
        if not traj:
            rospy.logdebug("traj path was empty!")
            return([], [])
        traj_length = len(traj.joint_trajectory.points)
        num_joints = len(traj.joint_trajectory.joint_names)

        #sanity-check max vels and accelerations
        if not max_joint_vels:
            max_joint_vels = [.2]*7
        elif len(max_joint_vels) != num_joints:
            rospy.logerr("invalid max_joint_vels!")
            return ([], [])
        if not max_joint_accs:
            max_joint_accs = [.5]*7
        elif len(max_joint_accs) != num_joints:
            rospy.logerr("invalid max_joint_accs!")
            return ([], [])
        for ind in range(num_joints):
            if max_joint_vels[ind] <= 0.:
                max_joint_vels[ind] = .2
            if max_joint_accs[ind] <= 0.:
                max_joint_accs[ind] = .5
            
        vels = [[None]*num_joints for i in range(traj_length)]
        
        #give the trajectory a bit of time to start
        segment_times = [None]*traj_length
        segment_times[0] = 0.05 

        #find vaguely appropriate segment times, assuming that we're traveling at max_joint_vels at the fastest joint
        for ind in range(traj_length-1):
            joint_diffs = [math.fabs(traj.joint_trajectory.points[ind+1].positions[x]-traj.joint_trajectory.points[ind].positions[x]) for x in range(num_joints)]
            joint_times = [diff/vel for (diff, vel) in zip(joint_diffs, max_joint_vels)]
            segment_times[ind+1] = max(joint_times+[min_segment_time])
            
        #set the initial and final velocities to 0 for all joints
        vels[0] = [0.]*num_joints
        vels[traj_length-1] = [0.]*num_joints

        #also set the velocity where any joint changes direction to be 0 for that joint
        #and otherwise use the average velocity (assuming piecewise-linear velocities for the segments before and after)
        for ind in range(1, traj_length-1):
            for joint in range(num_joints):
                diff0 = traj.joint_trajectory.points[ind].positions[joint]-traj.joint_trajectory.points[ind-1].positions[joint]
                diff1 = traj.joint_trajectory.points[ind+1].positions[joint]-traj.joint_trajectory.points[ind].positions[joint]
                if (diff0>0 and diff1<0) or (diff0<0 and diff1>0):
                    vels[ind][joint] = 0.
                else:
                    vel0 = diff0/segment_times[ind]
                    vel1 = diff1/segment_times[ind+1]
                    vels[ind][joint] = (vel0+vel1)/2.

        #increase the times if the desired velocities would require overly large accelerations
        for ind in range(1, traj_length):
            for joint in range(num_joints):
                veldiff = math.fabs(vels[ind][joint]-vels[ind-1][joint])
                acc = veldiff/segment_times[ind]
                try:
                    if acc > max_joint_accs[joint]:
                        segment_times[ind] = veldiff/max_joint_accs[joint]
                except:
                    pdb.set_trace()

        #turn the segment_times into waypoint times (cumulative)
        times = [None]*traj_length
        times[0] = segment_times[0]
        for ind in range(1, traj_length):
            try:
                times[ind] = times[ind-1]+segment_times[ind]
            except:
                rospy.logerr("could not add segment time")
                continue

        #return the times and velocities
        return (times, vels)
        
    def reset_planning_scene_(self):
        try:
            self.set_planning_scene_diff_.call()
        except:
            rospy.logerr("failed to reset the planning scene")
            
    def set_planning_scene_(self,attached_object_name):
        att_object = AttachedCollisionObject()
        att_object.link_name = "palm"
        att_object.object.id = attached_object_name
        att_object.object.operation.operation = CollisionObjectOperation.ATTACH_AND_REMOVE_AS_OBJECT
        att_object.object.header.frame_id = "palm"
        att_object.object.header.stamp = rospy.Time.now()
        object = Shape()
        object.type = Shape.CYLINDER
        object.dimensions.append(.03)
        object.dimensions.append(0.1)
        pose = Pose()
        pose.position.x = 0.0
        pose.position.y = -0.06
        pose.position.z = 0.06
        pose.orientation.x = 0
        pose.orientation.y = 0
        pose.orientation.z = 0
        pose.orientation.w = 1
        att_object.object.shapes.append(object)
        att_object.object.poses.append(pose);
        att_object.touch_links= ["ffdistal","mfdistal","rfdistal","lfdistal","thdistal","ffmiddle","mfmiddle","rfmiddle","lfmiddle","thmiddle","ffproximal","mfproximal","rfproximal","lfproximal","thproximal","palm","lfmetacarpal","thbase"]
        #att_object.touch_links.push_back("_end_effector");
        
        planning_scene_req = SetPlanningSceneDiffRequest()
        planning_scene_req.planning_scene_diff.attached_collision_objects.append(att_object);
        try:
            planning_scene_res=self.set_planning_scene_diff_.call(planning_scene_req)
        except:
            rospy.logerr("failed to set the planning scene")

if __name__ =="__main__":
    rospy.init_node("planification")
    plan = Planification()

    object_pose = PoseStamped()
    object_pose.pose.position.x = 0.470
    object_pose.pose.position.y = 0.166
    object_pose.pose.position.z = 1.665
    
    object_pose.pose.orientation.x = 0.375
    object_pose.pose.orientation.y = 0.155
    object_pose.pose.orientation.z = 0.844
    object_pose.pose.orientation.w = 0.351
    

    result = plan.plan_arm_motion( "right_arm", "jointspace", object_pose )
    rospy.logerr("got result " + str(result))
    rospy.spin()