00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090 import roslib; roslib.load_manifest('interpolated_ik_motion_planner')
00091 import rospy
00092 import interpolated_ik_motion_planner.ik_utilities as ik_utilities
00093 import math
00094 import sys
00095 import pdb
00096 from motion_planning_msgs.srv import GetMotionPlan, GetMotionPlanResponse
00097 from motion_planning_msgs.msg import ArmNavigationErrorCodes, RobotState
00098 from geometry_msgs.msg import PoseStamped, PointStamped, QuaternionStamped, Pose, Point, Quaternion
00099 from trajectory_msgs.msg import JointTrajectoryPoint
00100 from interpolated_ik_motion_planner.srv import SetInterpolatedIKMotionPlanParams, SetInterpolatedIKMotionPlanParamsResponse
00101 from sensor_msgs.msg import JointState
00102
00103
00104 class InterpolatedIKService:
00105
00106 def __init__(self, which_arm):
00107 self.which_arm = which_arm
00108 self.node_name = which_arm+'_interpolated_ik_motion_planner_server'
00109
00110 rospy.init_node(self.node_name)
00111
00112
00113
00114
00115 self.num_steps = rospy.get_param(self.node_name+'/num_steps', 6)
00116
00117
00118 self.consistent_angle = rospy.get_param(self.node_name+'/consistent_angle', math.pi/9)
00119
00120
00121 self.collision_check_resolution = rospy.get_param(self.node_name+'/collision_check_resolution', 1)
00122
00123
00124 self.steps_before_abort = rospy.get_param(self.node_name+'/steps_before_abort', 0)
00125
00126
00127 self.pos_spacing = rospy.get_param(self.node_name+'/pos_spacing', 0.01)
00128
00129
00130 self.rot_spacing = rospy.get_param(self.node_name+'/rot_spacing', .1)
00131
00132
00133 self.collision_aware = rospy.get_param(self.node_name+'/collision_aware', 1)
00134
00135
00136 self.start_from_end = rospy.get_param(self.node_name+'/start_from_end', 0)
00137
00138
00139 self.max_joint_vels = rospy.get_param(self.node_name+'/max_joint_vels', [.1]*7)
00140
00141
00142 self.max_joint_accs = rospy.get_param(self.node_name+'/max_joint_vels', [.25]*7)
00143
00144
00145 if which_arm == 'r':
00146 self.ik_utils = ik_utilities.IKUtilities('right')
00147 else:
00148 self.ik_utils = ik_utilities.IKUtilities('left')
00149
00150
00151 s1 = rospy.Service(which_arm+'_interpolated_ik_motion_plan', \
00152 GetMotionPlan, self.interpolated_ik_motion_planner_callback)
00153
00154
00155 s2 = rospy.Service(which_arm+'_interpolated_ik_motion_plan_set_params', \
00156 SetInterpolatedIKMotionPlanParams, self.set_params_callback)
00157
00158
00159
00160 def add_header(self, msg, frame):
00161 msg.header.frame_id = frame
00162 msg.header.stamp = rospy.Time()
00163 return msg
00164
00165
00166
00167 def pplist(self, list):
00168 return ' '.join(['%2.3f'%x for x in list])
00169
00170
00171
00172 def set_params_callback(self, req):
00173 self.num_steps = req.num_steps
00174 self.consistent_angle = req.consistent_angle
00175 self.collision_check_resolution= req.collision_check_resolution
00176 self.steps_before_abort = req.steps_before_abort
00177 self.pos_spacing = req.pos_spacing
00178 self.rot_spacing = req.rot_spacing
00179 self.collision_aware = req.collision_aware
00180 self.start_from_end = req.start_from_end
00181 self.max_joint_vels = req.max_joint_vels
00182 self.max_joint_accs = req.max_joint_accs
00183 return SetInterpolatedIKMotionPlanParamsResponse()
00184
00185
00186
00187 def interpolated_ik_motion_planner_callback(self, req):
00188
00189
00190 joint_names = req.motion_plan_request.start_state.joint_state.name
00191 start_angles = req.motion_plan_request.start_state.joint_state.position
00192
00193
00194 if start_angles and len(joint_names) != len(start_angles):
00195 rospy.logerr("start_state.joint_state.name needs to be the same length as start_state.joint_state.position! Quitting")
00196 return 0
00197
00198
00199 reordered_start_angles = []
00200
00201
00202 joint_states_msg = rospy.wait_for_message('joint_states', JointState, 10.0)
00203 if not joint_states_msg:
00204 rospy.logerr("unable to get joint_states message")
00205 return 0
00206
00207
00208
00209 for joint_name in self.ik_utils.joint_names:
00210
00211
00212 if joint_name in joint_names and start_angles:
00213 index = joint_names.index(joint_name)
00214 reordered_start_angles.append(start_angles[index])
00215
00216
00217 elif joint_name in joint_states_msg.name:
00218 index = joint_states_msg.name.index(joint_name)
00219 current_position = joint_states_msg.position[index]
00220 reordered_start_angles.append(current_position)
00221
00222
00223 else:
00224 rospy.logerr("an expected arm joint,"+joint_name+"was not found!")
00225 return 0
00226
00227
00228 additional_joint_angles = []
00229 additional_joint_names = []
00230 for (ind, joint_name) in enumerate(joint_names):
00231 if joint_name not in self.ik_utils.joint_names:
00232 rospy.loginfo("found %s"%joint_name)
00233 additional_joint_angles.append(start_angles[ind])
00234 additional_joint_names.append(joint_name)
00235 IK_robot_state = None
00236 if additional_joint_angles:
00237 rospy.loginfo("adding additional start angles for:"+str(additional_joint_names))
00238 rospy.loginfo("additional joint angles:"+str(additional_joint_angles))
00239 IK_robot_state = RobotState()
00240 IK_robot_state.joint_state.name = additional_joint_names
00241 IK_robot_state.joint_state.position = additional_joint_angles
00242
00243
00244 link_name = req.motion_plan_request.start_state.multi_dof_joint_state.child_frame_ids[0]
00245 if link_name != self.ik_utils.link_name:
00246 rospy.logerr("link_name not allowed: %s"%link_name)
00247 return 0
00248
00249
00250 start_pose = req.motion_plan_request.start_state.multi_dof_joint_state.poses[0]
00251
00252
00253 frame_id = req.motion_plan_request.start_state.multi_dof_joint_state.frame_ids[0]
00254
00255
00256 start_pose_stamped = self.add_header(PoseStamped(), frame_id)
00257 start_pose_stamped.pose = start_pose
00258
00259
00260 goal_pos = req.motion_plan_request.goal_constraints.position_constraints[0].position
00261
00262
00263 goal_pos_frame = req.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id
00264
00265
00266 goal_ps = self.add_header(PointStamped(), goal_pos_frame)
00267 goal_ps.point = goal_pos
00268 goal_pos_list = self.ik_utils.point_stamped_to_list(goal_ps, 'base_link')
00269
00270
00271 goal_quat = req.motion_plan_request.goal_constraints.orientation_constraints[0].orientation
00272
00273
00274 goal_quat_frame = req.motion_plan_request.goal_constraints.orientation_constraints[0].header.frame_id
00275
00276
00277 goal_qs = self.add_header(QuaternionStamped(), goal_quat_frame)
00278 goal_qs.quaternion = goal_quat
00279 goal_quat_list = self.ik_utils.quaternion_stamped_to_list(goal_qs, 'base_link')
00280
00281
00282 goal_pose_stamped = self.add_header(PoseStamped(), 'base_link')
00283 goal_pose_stamped.pose = Pose(Point(*goal_pos_list), Quaternion(*goal_quat_list))
00284
00285
00286 ordered_collision_operations = req.motion_plan_request.ordered_collision_operations
00287 if ordered_collision_operations.collision_operations == []:
00288 ordered_collision_operations = None
00289
00290
00291 link_padding = req.motion_plan_request.link_padding
00292 if link_padding == []:
00293 link_padding = None
00294
00295
00296 (trajectory, error_codes) = self.ik_utils.check_cartesian_path(start_pose_stamped, \
00297 goal_pose_stamped, reordered_start_angles, self.pos_spacing, self.rot_spacing, \
00298 self.consistent_angle, self.collision_aware, self.collision_check_resolution, \
00299 self.steps_before_abort, self.num_steps, ordered_collision_operations, \
00300 self.start_from_end, IK_robot_state, link_padding)
00301
00302
00303
00304 start_ind = 0
00305 stop_ind = len(error_codes)
00306 if self.start_from_end:
00307 for ind in range(len(error_codes)-1, 0, -1):
00308 if error_codes[ind]:
00309 start_ind = ind+1
00310 break
00311 else:
00312 for ind in range(len(error_codes)):
00313 if error_codes[ind]:
00314 stop_ind = ind
00315 break
00316 (times, vels) = self.ik_utils.trajectory_times_and_vels(trajectory[start_ind:stop_ind], self.max_joint_vels, self.max_joint_accs)
00317 times = [0]*start_ind + times + [0]*(len(error_codes)-stop_ind)
00318 vels = [[0]*7]*start_ind + vels + [[0]*7]*(len(error_codes)-stop_ind)
00319
00320 rospy.logdebug("trajectory:")
00321 for ind in range(len(trajectory)):
00322 rospy.logdebug("error code "+ str(error_codes[ind]) + " pos : " + self.pplist(trajectory[ind]))
00323 rospy.logdebug("")
00324 for ind in range(len(trajectory)):
00325 rospy.logdebug("time: " + "%5.3f "%times[ind] + "vels: " + self.pplist(vels[ind]))
00326
00327
00328 res = GetMotionPlanResponse()
00329
00330
00331 res.trajectory.joint_trajectory.joint_names = self.ik_utils.joint_names[:]
00332
00333
00334
00335 res.trajectory.joint_trajectory.points = []
00336 for i in range(len(trajectory)):
00337 joint_trajectory_point = JointTrajectoryPoint()
00338 joint_trajectory_point.positions = trajectory[i]
00339 joint_trajectory_point.velocities = vels[i]
00340 joint_trajectory_point.time_from_start = rospy.Duration(times[i])
00341 res.trajectory.joint_trajectory.points.append(joint_trajectory_point)
00342
00343
00344
00345
00346
00347
00348
00349 error_code_dict = {0:ArmNavigationErrorCodes.SUCCESS, 1:ArmNavigationErrorCodes.COLLISION_CONSTRAINTS_VIOLATED, \
00350 2:ArmNavigationErrorCodes.PATH_CONSTRAINTS_VIOLATED, 3:ArmNavigationErrorCodes.JOINT_LIMITS_VIOLATED, \
00351 4:ArmNavigationErrorCodes.PLANNING_FAILED}
00352
00353 trajectory_error_codes = [ArmNavigationErrorCodes(val=error_code_dict[error_code]) for error_code in error_codes]
00354 res.trajectory_error_codes = trajectory_error_codes
00355
00356
00357
00358
00359
00360
00361
00362
00363 return res
00364
00365
00366 if __name__ == "__main__":
00367
00368 if len(sys.argv) < 2 or sys.argv[1] != 'r' and sys.argv[1] != 'l':
00369 rospy.logerr("usage: interpolated_ik_motion_planner.py which_arm (which_arm is r or l)")
00370 sys.exit(1)
00371
00372 which_arm = sys.argv[1]
00373 interpolated_ik_service = InterpolatedIKService(which_arm)
00374 rospy.loginfo("Ready to serve interpolated IK motion plan requests.")
00375
00376 rospy.spin()
00377