simple_moveit_interface.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import threading
19 from copy import deepcopy
20 
21 import rospy
22 from geometry_msgs.msg import PoseStamped
23 from moveit_commander import MoveGroupCommander, PlanningSceneInterface
24 import tf
25 
26 
27 
28 
29 
30 _transform_listener = None
31 _transform_listener_creation_lock = threading.Lock()
32 
33 _mgc_dict = dict()
34 _mgc_dict_creation_lock = threading.Lock()
35 
36 _psi = None
37 _psi_creation_lock = threading.Lock()
38 
40  '''
41  Gets the transform listener for this process.
42  This is needed because tf only allows one transform listener per process. Threadsafe, so
43  that two threads could call this at the same time, at it will do the right thing.
44  '''
45  global _transform_listener
46  with _transform_listener_creation_lock:
47  if _transform_listener == None:
48  _transform_listener = tf.TransformListener()
49  return _transform_listener
50 
51 
52 
54  '''
55  Gets the move_group_commander for this process.
56  '''
57  global _mgc_dict
58  with _mgc_dict_creation_lock:
59  if not group in _mgc_dict:
60  _mgc_group = MoveGroupCommander(group)
61  _mgc_group.set_planner_id('RRTConnectkConfigDefault')
62  _mgc_dict[group] = _mgc_group
63 
64  add_ground()
65  return _mgc_dict[group]
66 
67 
68 
70  '''
71  Gets the planning_scene_interface for this process.
72  '''
73  global _psi
74  with _psi_creation_lock:
75  if _psi == None:
76  _psi = PlanningSceneInterface()
77  return _psi
78 
79 
80 def add_ground():
82  pose = PoseStamped()
83  pose.pose.position.x = 0
84  pose.pose.position.y = 0
85  # offset such that the box is 0.1 mm below ground (to prevent collision with the robot itself)
86  pose.pose.position.z = -0.0501
87  pose.pose.orientation.x = 0
88  pose.pose.orientation.y = 0
89  pose.pose.orientation.z = 0
90  pose.pose.orientation.w = 1
91  pose.header.stamp = rospy.get_rostime()
92  pose.header.frame_id = "base_link"
93  psi.attach_box("base_link", "ground", pose, (3, 3, 0.1))
94 
95 #ToDo: attached objects are not removed
98  psi.remove_world_object("")
99 
100 def clear_attached_object(attach_link, object_name=None):
102  psi.remove_attached_object(link = attach_link, name = object_name)
103  psi.remove_world_object(object_name)
104 
105 
106 def attach_mesh_to_link(link, name, path):
108  pose = PoseStamped()
109  pose.pose.orientation.w = 1
110  pose.header.stamp = rospy.get_rostime()
111  pose.header.frame_id = link
112  psi.attach_mesh(link, name, pose, path)
113 
114 def moveit_joint_goal(group, goal, replanning=False):
115  mgc = get_move_group_commander(group)
116  mgc.allow_replanning(replanning)
117  if mgc.go(goal):
118  print("Done moving")
119  return 'succeeded'
120  else:
121  print("Failed to plan path")
122  return 'failed'
123 
124 def moveit_pose_goal(group, ref_frame, goal, replan=False):
125  mgc = get_move_group_commander(group)
126  mgc.allow_replanning(replan)
127  mgc.set_pose_reference_frame(ref_frame)
128  ret = mgc.go(goal)
129  mgc.allow_replanning(False)
130  if ret:
131  print("Done moving")
132  return 'succeeded'
133  else:
134  print("Failed to plan path")
135  return 'failed'
136 
137 
138 
139 #this is linear movement
140 def moveit_cart_goals(group, ref_frame, goal_list, avoid_collisions=True):
141  mgc = get_move_group_commander(group)
142 
143  mgc.set_pose_reference_frame(ref_frame)
144  (traj,frac) = mgc.compute_cartesian_path(goal_list, 0.01, 4, avoid_collisions)
145  print(traj,frac)
146 
147  #mgc.execute(traj)
148  #print "Done moving"
149  #return 'succeeded'
150 
151  if frac == 1.0:
152  if mgc.execute(traj):
153  print("Done moving")
154  return 'succeeded'
155  else:
156  print("Something happened during execution")
157  return 'failed'
158  else:
159  print("Failed to plan full path!")
160  return 'failed'
161 
162 
164  mgc = get_move_group_commander(group)
165 
166  cp = mgc.get_current_pose()
167  cp.header.stamp = rospy.Time()
168  return cp
169 
170 
171 
172 
173 
174 
175 
176 ####################################
177 # helpers
178 ####################################
179 
180 def get_goal_from_server(group, parameter_name):
181  ns_global_prefix = "/script_server"
182 
183  # get joint_names from parameter server
184  param_string = ns_global_prefix + "/" + group + "/joint_names"
185  if not rospy.has_param(param_string):
186  rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",param_string)
187  return None
188  joint_names = rospy.get_param(param_string)
189 
190  # check joint_names parameter
191  if not type(joint_names) is list: # check list
192  rospy.logerr("no valid joint_names for %s: not a list, aborting...",group)
193  print("joint_names are:",joint_names)
194  return None
195  else:
196  for i in joint_names:
197  if not type(i) is str: # check string
198  rospy.logerr("no valid joint_names for %s: not a list of strings, aborting...",group)
199  print("joint_names are:",joint_names)
200  return None
201  else:
202  rospy.logdebug("accepted joint_names for group %s",group)
203 
204  # get joint values from parameter server
205  if type(parameter_name) is str:
206  if not rospy.has_param(ns_global_prefix + "/" + group + "/" + parameter_name):
207  rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",ns_global_prefix + "/" + group + "/" + parameter_name)
208  return None
209  param = rospy.get_param(ns_global_prefix + "/" + group + "/" + parameter_name)
210  else:
211  param = parameter_name
212 
213  # check trajectory parameters
214  if not type(param) is list: # check outer list
215  rospy.logerr("no valid parameter for %s: not a list, aborting...",group)
216  print("parameter is:",param)
217  return None
218 
219  #no need for trajectories anymore, since planning (will) guarantee collision-free motion!
220  point = param[len(param)-1]
221 
222  #print point,"type1 = ", type(point)
223  if type(point) is str:
224  if not rospy.has_param(ns_global_prefix + "/" + group + "/" + point):
225  rospy.logerr("parameter %s does not exist on ROS Parameter Server, aborting...",ns_global_prefix + "/" + group + "/" + point)
226  return None
227  point = rospy.get_param(ns_global_prefix + "/" + group + "/" + point)
228  point = point[0] # \todo TODO: hack because only first point is used, no support for trajectories inside trajectories
229  #print point
230  elif type(point) is list:
231  rospy.logdebug("point is a list")
232  else:
233  rospy.logerr("no valid parameter for %s: not a list of lists or strings, aborting...",group)
234  print("parameter is:",param)
235  return None
236 
237  # here: point should be list of floats/ints
238  #print point
239  if not len(point) == len(joint_names): # check dimension
240  rospy.logerr("no valid parameter for %s: dimension should be %d and is %d, aborting...",group,len(joint_names),len(point))
241  print("parameter is:",param)
242  return None
243 
244  for value in point:
245  #print value,"type2 = ", type(value)
246  if not ((type(value) is float) or (type(value) is int)): # check type
247  #print type(value)
248  rospy.logerr("no valid parameter for %s: not a list of float or int, aborting...",group)
249  print("parameter is:",param)
250  return None
251  rospy.logdebug("accepted value %f for %s",value,group)
252 
253  return point
254 
255 
256 
257 
258 
259 
260 
261 
262 
263 
264 
def clear_attached_object(attach_link, object_name=None)
def moveit_pose_goal(group, ref_frame, goal, replan=False)
def get_goal_from_server(group, parameter_name)
helpers
def moveit_cart_goals(group, ref_frame, goal_list, avoid_collisions=True)
def moveit_joint_goal(group, goal, replanning=False)


cob_moveit_interface
Author(s): Felix Messmer
autogenerated on Sun Dec 6 2020 03:25:57