simple_moveit_interface.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 import threading
00019 from copy import deepcopy
00020 
00021 import rospy
00022 from geometry_msgs.msg import PoseStamped
00023 from moveit_commander import MoveGroupCommander, PlanningSceneInterface
00024 import tf
00025 
00026 
00027 
00028 
00029 
00030 _transform_listener = None
00031 _transform_listener_creation_lock = threading.Lock()
00032 
00033 _mgc_dict = dict()
00034 _mgc_dict_creation_lock = threading.Lock()
00035 
00036 _psi = None
00037 _psi_creation_lock = threading.Lock()
00038 
00039 def get_transform_listener():
00040     '''
00041     Gets the transform listener for this process.
00042 
00043     This is needed because tf only allows one transform listener per process. Threadsafe, so
00044     that two threads could call this at the same time, at it will do the right thing.
00045     '''
00046     global _transform_listener
00047     with _transform_listener_creation_lock:
00048         if _transform_listener == None:
00049             _transform_listener = tf.TransformListener()
00050         return _transform_listener
00051 
00052 
00053 
00054 def get_move_group_commander(group):
00055     '''
00056     Gets the move_group_commander for this process.
00057 
00058     '''
00059     global _mgc_dict
00060     with _mgc_dict_creation_lock:
00061         if not group in _mgc_dict:
00062             _mgc_group = MoveGroupCommander(group)
00063             _mgc_group.set_planner_id('RRTConnectkConfigDefault')
00064             _mgc_dict[group] = _mgc_group
00065             add_ground()
00066         return _mgc_dict[group]
00067 
00068 
00069 
00070 def get_planning_scene_interface():
00071     '''
00072     Gets the planning_scene_interface for this process.
00073 
00074     '''
00075     global _psi
00076     with _psi_creation_lock:
00077         if _psi == None:
00078             _psi = PlanningSceneInterface()
00079         return _psi
00080 
00081 
00082 def add_ground():
00083     psi = get_planning_scene_interface()
00084     pose = PoseStamped()
00085     pose.pose.position.x = 0
00086     pose.pose.position.y = 0
00087     # offset such that the box is 0.1 mm below ground (to prevent collision with the robot itself)
00088     pose.pose.position.z = -0.0501
00089     pose.pose.orientation.x = 0
00090     pose.pose.orientation.y = 0
00091     pose.pose.orientation.z = 0
00092     pose.pose.orientation.w = 1
00093     pose.header.stamp = rospy.get_rostime()
00094     pose.header.frame_id = "base_link"
00095     psi.attach_box("base_link", "ground", pose, (3, 3, 0.1))
00096 
00097 def clear_objects(attach_link):
00098     psi = get_planning_scene_interface()
00099     psi.remove_attached_object(attach_link)
00100     psi.remove_world_object("")
00101 
00102 def clear_attached_object(attach_link, object_name):
00103     psi = get_planning_scene_interface()
00104     psi.remove_attached_object(link = attach_link, name = object_name)
00105     psi.remove_world_object(object_name)
00106 
00107 
00108 def attach_mesh_to_link(link, name, path):
00109     psi = get_planning_scene_interface()
00110     pose = PoseStamped()
00111     pose.pose.orientation.w = 1
00112     pose.header.stamp = rospy.get_rostime()
00113     pose.header.frame_id = link
00114     psi.attach_mesh(link, name, pose, path)
00115 
00116 def moveit_joint_goal(group, goal, replanning=False):
00117     mgc = get_move_group_commander(group)
00118     mgc.allow_replanning(replanning)
00119     if mgc.go(goal):
00120         print "Done moving"
00121         return 'succeeded'
00122     else:
00123         print "Failed to plan path"
00124         return 'failed'
00125 
00126 def moveit_pose_goal(group, ref_frame, goal, replan=False):
00127     mgc = get_move_group_commander(group)
00128     mgc.allow_replanning(replan)
00129     mgc.set_pose_reference_frame(ref_frame)
00130     ret = mgc.go(goal)
00131     mgc.allow_replanning(False)
00132     if ret:
00133         print "Done moving"
00134         return 'succeeded'
00135     else:
00136         print "Failed to plan path"
00137         return 'failed'
00138 
00139 
00140 
00141 #this is linear movement
00142 def moveit_cart_goals(group, ref_frame, goal_list, avoid_collisions=True):
00143     mgc = get_move_group_commander(group)
00144 
00145     mgc.set_pose_reference_frame(ref_frame)
00146     (traj,frac)  = mgc.compute_cartesian_path(goal_list, 0.01, 4, avoid_collisions)
00147     print traj,frac
00148 
00149     #mgc.execute(traj)
00150     #print "Done moving"
00151     #return 'succeeded'
00152 
00153     if frac == 1.0:
00154         if mgc.execute(traj):
00155                 print "Done moving"
00156                 return 'succeeded'
00157         else:
00158                 print "Something happened during execution"
00159                 print 'failed'
00160     else:
00161         print "Failed to plan full path!"
00162         return 'failed'
00163 
00164 
00165 def moveit_get_current_pose(group):
00166     mgc = get_move_group_commander(group)
00167 
00168     cp = mgc.get_current_pose()
00169     cp.header.stamp = rospy.Time()
00170     return cp
00171 
00172 
00173 
00174 
00175 
00176 
00177 
00178 ####################################
00179 #  helpers
00180 ####################################
00181 
00182 def get_goal_from_server(group, parameter_name):
00183 
00184         ns_global_prefix = "/script_server"
00185 
00186         # get joint_names from parameter server
00187         param_string = ns_global_prefix + "/" + group + "/joint_names"
00188         if not rospy.has_param(param_string):
00189                 rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",param_string)
00190                 return None
00191         joint_names = rospy.get_param(param_string)
00192 
00193         # check joint_names parameter
00194         if not type(joint_names) is list: # check list
00195                 rospy.logerr("no valid joint_names for %s: not a list, aborting...",group)
00196                 print "joint_names are:",joint_names
00197                 return None
00198         else:
00199             for i in joint_names:
00200                 if not type(i) is str: # check string
00201                     rospy.logerr("no valid joint_names for %s: not a list of strings, aborting...",group)
00202                     print "joint_names are:",joint_names
00203                     return None
00204                 else:
00205                     rospy.logdebug("accepted joint_names for group %s",group)
00206 
00207         # get joint values from parameter server
00208         if type(parameter_name) is str:
00209             if not rospy.has_param(ns_global_prefix + "/" + group + "/" + parameter_name):
00210                 rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",ns_global_prefix + "/" + group + "/" + parameter_name)
00211                 return None
00212             param = rospy.get_param(ns_global_prefix + "/" + group + "/" + parameter_name)
00213         else:
00214             param = parameter_name
00215 
00216         # check trajectory parameters
00217         if not type(param) is list: # check outer list
00218                 rospy.logerr("no valid parameter for %s: not a list, aborting...",group)
00219                 print "parameter is:",param
00220                 return None
00221 
00222 
00223         #no need for trajectories anymore, since planning (will) guarantee collision-free motion!
00224         point = param[len(param)-1]
00225 
00226         #print point,"type1 = ", type(point)
00227         if type(point) is str:
00228             if not rospy.has_param(ns_global_prefix + "/" + group + "/" + point):
00229                 rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",ns_global_prefix + "/" + group + "/" + point)
00230                 return None
00231             point = rospy.get_param(ns_global_prefix + "/" + group + "/" + point)
00232             point = point[0] # \todo TODO: hack because only first point is used, no support for trajectories inside trajectories
00233             #print point
00234         elif type(point) is list:
00235             rospy.logdebug("point is a list")
00236         else:
00237             rospy.logerr("no valid parameter for %s: not a list of lists or strings, aborting...",group)
00238             print "parameter is:",param
00239             return None
00240 
00241         # here: point should be list of floats/ints
00242         #print point
00243         if not len(point) == len(joint_names): # check dimension
00244             rospy.logerr("no valid parameter for %s: dimension should be %d and is %d, aborting...",group,len(joint_names),len(point))
00245             print "parameter is:",param
00246             return None
00247 
00248         for value in point:
00249             #print value,"type2 = ", type(value)
00250             if not ((type(value) is float) or (type(value) is int)): # check type
00251                 #print type(value)
00252                 rospy.logerr("no valid parameter for %s: not a list of float or int, aborting...",group)
00253                 print "parameter is:",param
00254                 return None
00255             rospy.logdebug("accepted value %f for %s",value,group)
00256 
00257         return point
00258 
00259 
00260 
00261 
00262 
00263 
00264 
00265 
00266 
00267 
00268 


cob_moveit_interface
Author(s): Felix Messmer
autogenerated on Thu Jun 6 2019 21:23:08