moveit2
The MoveIt Motion Planning Framework for ROS 2.
moveitjoy_module.py
Go to the documentation of this file.
1 # ********************************************************************
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2014, JSK, The University of Tokyo.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of the JSK, The University of Tokyo nor the names of its
18 # nor the names of its contributors may be
19 # used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 # ********************************************************************/
35 
36 # Author: Ryohei Ueda, Dave Coleman
37 # Desc: Interface between PS3/XBox controller and MoveIt Motion Planning Rviz Plugin
38 
39 from __future__ import print_function
40 
41 import xml.dom.minidom
42 from operator import add
43 import sys
44 import threading
45 from moveit_ros_planning_interface._moveit_robot_interface import RobotInterface
46 
47 import rospy
48 import roslib
49 import numpy
50 import time
51 import tf
52 from std_msgs.msg import Empty, String
53 from sensor_msgs.msg import Joy
54 from geometry_msgs.msg import PoseStamped
55 from visualization_msgs.msg import InteractiveMarkerInit
56 
57 
58 def signedSquare(val):
59  if val > 0:
60  sign = 1
61  else:
62  sign = -1
63  return val * val * sign
64 
65 
66 # classes to use joystick of xbox, ps3(wired) and ps3(wireless).
67 
68 
69 class JoyStatus:
70  def __init__(self):
71  self.centercenter = False
72  self.selectselect = False
73  self.startstart = False
74  self.L3L3 = False
75  self.R3R3 = False
76  self.squaresquare = False
77  self.upup = False
78  self.downdown = False
79  self.leftleft = False
80  self.rightright = False
81  self.triangletriangle = False
82  self.crosscross = False
83  self.circlecircle = False
84  self.L1L1 = False
85  self.R1R1 = False
86  self.L2L2 = False
87  self.R2R2 = False
88  self.left_analog_xleft_analog_x = 0.0
89  self.left_analog_yleft_analog_y = 0.0
90  self.right_analog_xright_analog_x = 0.0
91  self.right_analog_yright_analog_y = 0.0
92 
93 
95  def __init__(self, msg):
96  JoyStatus.__init__(self)
97  self.centercentercenter = msg.buttons[8] == 1
98  self.selectselectselect = msg.buttons[6] == 1
99  self.startstartstart = msg.buttons[7] == 1
100  self.L3L3L3 = msg.buttons[9] == 1
101  self.R3R3R3 = msg.buttons[10] == 1
102  self.squaresquaresquare = msg.buttons[2] == 1
103  self.circlecirclecircle = msg.buttons[1] == 1
104  self.upupup = msg.axes[7] > 0.1
105  self.downdowndown = msg.axes[7] < -0.1
106  self.leftleftleft = msg.axes[6] > 0.1
107  self.rightrightright = msg.axes[6] < -0.1
108  self.triangletriangletriangle = msg.buttons[3] == 1
109  self.crosscrosscross = msg.buttons[0] == 1
110  self.L1L1L1 = msg.buttons[4] == 1
111  self.R1R1R1 = msg.buttons[5] == 1
112  self.L2L2L2 = msg.axes[2] < -0.5
113  self.R2R2R2 = msg.axes[5] < -0.5
114  self.left_analog_xleft_analog_xleft_analog_x = msg.axes[0]
115  self.left_analog_yleft_analog_yleft_analog_y = msg.axes[1]
116  self.right_analog_xright_analog_xright_analog_x = msg.axes[3]
117  self.right_analog_yright_analog_yright_analog_y = msg.axes[4]
118  self.orig_msgorig_msg = msg
119 
120 
122  def __init__(self, msg):
123  JoyStatus.__init__(self)
124  # creating from sensor_msgs/Joy
125  self.crosscrosscross = msg.buttons[0] == 1
126  self.circlecirclecircle = msg.buttons[1] == 1
127  self.triangletriangletriangle = msg.buttons[2] == 1
128  self.squaresquaresquare = msg.buttons[3] == 1
129  self.L1L1L1 = msg.buttons[4] == 1
130  self.R1R1R1 = msg.buttons[5] == 1
131  self.L2L2L2 = msg.buttons[6] == 1
132  self.R2R2R2 = msg.buttons[7] == 1
133  self.selectselectselect = msg.buttons[8] == 1
134  self.startstartstart = msg.buttons[9] == 1
135  self.centercentercenter = msg.buttons[10] == 1
136  self.left_analog_xleft_analog_xleft_analog_x = msg.axes[0]
137  self.left_analog_yleft_analog_yleft_analog_y = msg.axes[1]
138  self.right_analog_xright_analog_xright_analog_x = msg.axes[3]
139  self.right_analog_yright_analog_yright_analog_y = msg.axes[4]
140 
141  self.orig_msgorig_msg = msg
142 
143 
145  def __init__(self, msg):
146  JoyStatus.__init__(self)
147  # creating from sensor_msgs/Joy
148  self.centercentercenter = msg.buttons[16] == 1
149  self.selectselectselect = msg.buttons[0] == 1
150  self.startstartstart = msg.buttons[3] == 1
151  self.L3L3L3 = msg.buttons[1] == 1
152  self.R3R3R3 = msg.buttons[2] == 1
153  self.squaresquaresquare = msg.axes[15] < 0
154  self.upupup = msg.axes[4] < 0
155  self.downdowndown = msg.axes[6] < 0
156  self.leftleftleft = msg.axes[7] < 0
157  self.rightrightright = msg.axes[5] < 0
158  self.triangletriangletriangle = msg.axes[12] < 0
159  self.crosscrosscross = msg.axes[14] < 0
160  self.circlecirclecircle = msg.axes[13] < 0
161  self.L1L1L1 = msg.axes[10] < 0
162  self.R1R1R1 = msg.axes[11] < 0
163  self.L2L2L2 = msg.axes[8] < 0
164  self.R2R2R2 = msg.axes[9] < 0
165  self.left_analog_xleft_analog_xleft_analog_x = msg.axes[0]
166  self.left_analog_yleft_analog_yleft_analog_y = msg.axes[1]
167  self.right_analog_xright_analog_xright_analog_x = msg.axes[2]
168  self.right_analog_yright_analog_yright_analog_y = msg.axes[3]
169  self.orig_msgorig_msg = msg
170 
171 
173  def __init__(self, msg):
174  JoyStatus.__init__(self)
175  # creating from sensor_msgs/Joy
176  self.centercentercenter = msg.buttons[16] == 1
177  self.selectselectselect = msg.buttons[0] == 1
178  self.startstartstart = msg.buttons[3] == 1
179  self.L3L3L3 = msg.buttons[1] == 1
180  self.R3R3R3 = msg.buttons[2] == 1
181  self.squaresquaresquare = msg.buttons[15] == 1
182  self.upupup = msg.buttons[4] == 1
183  self.downdowndown = msg.buttons[6] == 1
184  self.leftleftleft = msg.buttons[7] == 1
185  self.rightrightright = msg.buttons[5] == 1
186  self.triangletriangletriangle = msg.buttons[12] == 1
187  self.crosscrosscross = msg.buttons[14] == 1
188  self.circlecirclecircle = msg.buttons[13] == 1
189  self.L1L1L1 = msg.buttons[10] == 1
190  self.R1R1R1 = msg.buttons[11] == 1
191  self.L2L2L2 = msg.buttons[8] == 1
192  self.R2R2R2 = msg.buttons[9] == 1
193  self.left_analog_xleft_analog_xleft_analog_x = msg.axes[0]
194  self.left_analog_yleft_analog_yleft_analog_y = msg.axes[1]
195  self.right_analog_xright_analog_xright_analog_x = msg.axes[2]
196  self.right_analog_yright_analog_yright_analog_y = msg.axes[3]
197  self.orig_msgorig_msg = msg
198 
199 
201  def __init__(self, msg):
202  JoyStatus.__init__(self)
203  # creating from sensor_msg/Joy
204  self.centercentercenter = msg.buttons[12] == 1
205  self.selectselectselect = msg.buttons[8] == 1
206  self.startstartstart = msg.buttons[9] == 1
207  self.L3L3L3 = msg.buttons[10] == 1
208  self.R3R3R3 = msg.buttons[11] == 1
209  self.squaresquaresquare = msg.buttons[0] == 1
210  self.upupup = msg.axes[10] < 0
211  self.downdowndown = msg.axes[10] > 0
212  self.leftleftleft = msg.axes[9] < 0
213  self.rightrightright = msg.axes[9] > 0
214  self.triangletriangletriangle = msg.buttons[3] == 1
215  self.crosscrosscross = msg.buttons[1] == 1
216  self.circlecirclecircle = msg.buttons[2] == 1
217  self.L1L1L1 = msg.buttons[4] == 1
218  self.R1R1R1 = msg.buttons[5] == 1
219  self.L2L2L2 = msg.buttons[6] == 1
220  self.R2R2R2 = msg.buttons[7] == 1
221  self.left_analog_xleft_analog_xleft_analog_x = msg.axes[0]
222  self.left_analog_yleft_analog_yleft_analog_y = msg.axes[1]
223  self.right_analog_xright_analog_xright_analog_x = msg.axes[5]
224  self.right_analog_yright_analog_yright_analog_y = msg.axes[2]
225  self.orig_msgorig_msg = msg
226 
227 
229  def __init__(self, msg):
230  JoyStatus.__init__(self)
231  # creating from sensor_msg/Joy
232  self.centercentercenter = msg.buttons[10] == 1
233  self.selectselectselect = msg.buttons[8] == 1
234  self.startstartstart = msg.buttons[9] == 1
235  self.L3L3L3 = msg.buttons[11] == 1
236  self.R3R3R3 = msg.buttons[12] == 1
237  self.squaresquaresquare = msg.buttons[3] == 1
238  self.upupup = msg.axes[7] < 0
239  self.downdowndown = msg.axes[7] > 0
240  self.leftleftleft = msg.axes[6] < 0
241  self.rightrightright = msg.axes[6] > 0
242  self.triangletriangletriangle = msg.buttons[2] == 1
243  self.crosscrosscross = msg.buttons[0] == 1
244  self.circlecirclecircle = msg.buttons[1] == 1
245  self.L1L1L1 = msg.buttons[4] == 1
246  self.R1R1R1 = msg.buttons[5] == 1
247  self.L2L2L2 = msg.buttons[6] == 1
248  self.R2R2R2 = msg.buttons[7] == 1
249  self.left_analog_xleft_analog_xleft_analog_x = msg.axes[0]
250  self.left_analog_yleft_analog_yleft_analog_y = msg.axes[1]
251  self.right_analog_xright_analog_xright_analog_x = msg.axes[3]
252  self.right_analog_yright_analog_yright_analog_y = msg.axes[4]
253  self.orig_msgorig_msg = msg
254 
255 
257  def __init__(self, max_length=10):
258  self.max_lengthmax_length = max_length
259  self.bufferbuffer = []
260 
261  def add(self, status):
262  self.bufferbuffer.append(status)
263  if len(self.bufferbuffer) > self.max_lengthmax_length:
264  self.bufferbuffer = self.bufferbuffer[1 : self.max_lengthmax_length + 1]
265 
266  def all(self, proc):
267  for status in self.bufferbuffer:
268  if not proc(status):
269  return False
270  return True
271 
272  def latest(self):
273  if len(self.bufferbuffer) > 0:
274  return self.bufferbuffer[-1]
275  else:
276  return None
277 
278  def length(self):
279  return len(self.bufferbuffer)
280 
281  def new(self, status, attr):
282  if len(self.bufferbuffer) == 0:
283  return getattr(status, attr)
284  else:
285  return getattr(status, attr) and not getattr(self.latestlatest(), attr)
286 
287 
288 class MoveitJoy:
289  def parseSRDF(self):
290  ri = RobotInterface("/robot_description")
291  planning_groups = {}
292  for g in ri.get_group_names():
293  self.planning_groups_tipsplanning_groups_tips[g] = ri.get_group_joint_tips(g)
294  if len(self.planning_groups_tipsplanning_groups_tips[g]) > 0:
295  planning_groups[g] = [
296  "/rviz/moveit/move_marker/goal_" + l
297  for l in self.planning_groups_tipsplanning_groups_tips[g]
298  ]
299  for name in planning_groups.keys():
300  print(name, planning_groups[name])
301  self.planning_groupsplanning_groups = planning_groups
302  self.planning_groups_keysplanning_groups_keys = list(
303  planning_groups.keys()
304  ) # we'd like to store the 'order'
305  self.frame_idframe_id = ri.get_planning_frame()
306 
307  def __init__(self):
308  self.initial_posesinitial_poses = {}
309  self.planning_groups_tipsplanning_groups_tips = {}
310  self.tf_listenertf_listener = tf.TransformListener()
311  self.marker_lockmarker_lock = threading.Lock()
312  self.prev_timeprev_time = rospy.Time.now()
313  self.countercounter = 0
314  self.historyhistory = StatusHistory(max_length=10)
315  self.pre_posepre_pose = PoseStamped()
316  self.pre_posepre_pose.pose.orientation.w = 1
317  self.current_planning_group_indexcurrent_planning_group_index = 0
318  self.current_eef_indexcurrent_eef_index = 0
319  self.initialize_posesinitialize_poses = False
320  self.initializedinitialized = False
321  self.parseSRDFparseSRDF()
322  self.plan_group_pubplan_group_pub = rospy.Publisher(
323  "/rviz/moveit/select_planning_group", String, queue_size=5
324  )
325  self.updatePlanningGroupupdatePlanningGroup(0)
326  self.updatePoseTopicupdatePoseTopic(0, False)
327  self.joy_pose_pubjoy_pose_pub = rospy.Publisher("/joy_pose", PoseStamped, queue_size=1)
328  self.plan_pubplan_pub = rospy.Publisher("/rviz/moveit/plan", Empty, queue_size=5)
329  self.execute_pubexecute_pub = rospy.Publisher("/rviz/moveit/execute", Empty, queue_size=5)
330  self.update_start_state_pubupdate_start_state_pub = rospy.Publisher(
331  "/rviz/moveit/update_start_state", Empty, queue_size=5
332  )
333  self.update_goal_state_pubupdate_goal_state_pub = rospy.Publisher(
334  "/rviz/moveit/update_goal_state", Empty, queue_size=5
335  )
336  self.interactive_marker_subinteractive_marker_sub = rospy.Subscriber(
337  "/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/update_full",
338  InteractiveMarkerInit,
339  self.markerCBmarkerCB,
340  queue_size=1,
341  )
342  self.subsub = rospy.Subscriber("/joy", Joy, self.joyCBjoyCB, queue_size=1)
343 
344  def updatePlanningGroup(self, next_index):
345  if next_index >= len(self.planning_groups_keysplanning_groups_keys):
346  self.current_planning_group_indexcurrent_planning_group_index = 0
347  elif next_index < 0:
348  self.current_planning_group_indexcurrent_planning_group_index = len(self.planning_groups_keysplanning_groups_keys) - 1
349  else:
350  self.current_planning_group_indexcurrent_planning_group_index = next_index
351  next_planning_group = None
352  try:
353  next_planning_group = self.planning_groups_keysplanning_groups_keys[
354  self.current_planning_group_indexcurrent_planning_group_index
355  ]
356  except IndexError:
357  msg = "Check if you started movegroups. Exiting."
358  rospy.logfatal(msg)
359  raise rospy.ROSInitException(msg)
360  rospy.loginfo("Changed planning group to " + next_planning_group)
361  self.plan_group_pubplan_group_pub.publish(next_planning_group)
362 
363  def updatePoseTopic(self, next_index, wait=True):
364  planning_group = self.planning_groups_keysplanning_groups_keys[self.current_planning_group_indexcurrent_planning_group_index]
365  topics = self.planning_groupsplanning_groups[planning_group]
366  if next_index >= len(topics):
367  self.current_eef_indexcurrent_eef_index = 0
368  elif next_index < 0:
369  self.current_eef_indexcurrent_eef_index = len(topics) - 1
370  else:
371  self.current_eef_indexcurrent_eef_index = next_index
372  next_topic = topics[self.current_eef_indexcurrent_eef_index]
373 
374  rospy.loginfo(
375  "Changed controlled end effector to "
376  + self.planning_groups_tipsplanning_groups_tips[planning_group][self.current_eef_indexcurrent_eef_index]
377  )
378  self.pose_pubpose_pub = rospy.Publisher(next_topic, PoseStamped, queue_size=5)
379  if wait:
380  self.waitForInitialPosewaitForInitialPose(next_topic)
381  self.current_pose_topiccurrent_pose_topic = next_topic
382 
383  def markerCB(self, msg):
384  try:
385  self.marker_lockmarker_lock.acquire()
386  if not self.initialize_posesinitialize_poses:
387  return
388  self.initial_posesinitial_poses = {}
389  for marker in msg.markers:
390  if marker.name.startswith("EE:goal_"):
391  # resolve tf
392  if marker.header.frame_id != self.frame_idframe_id:
393  ps = PoseStamped(header=marker.header, pose=marker.pose)
394  try:
395  transformed_pose = self.tf_listenertf_listener.transformPose(
396  self.frame_idframe_id, ps
397  )
398  self.initial_posesinitial_poses[marker.name[3:]] = transformed_pose.pose
399  except (
400  tf.LookupException,
401  tf.ConnectivityException,
402  tf.ExtrapolationException,
403  e,
404  ):
405  rospy.logerr("tf error when resolving tf: %s" % e)
406  else:
407  self.initial_posesinitial_poses[
408  marker.name[3:]
409  ] = marker.pose # tf should be resolved
410  finally:
411  self.marker_lockmarker_lock.release()
412 
413  def waitForInitialPose(self, next_topic, timeout=None):
414  counter = 0
415  while not rospy.is_shutdown():
416  counter = counter + 1
417  if timeout and counter >= timeout:
418  return False
419  try:
420  self.marker_lockmarker_lock.acquire()
421  self.initialize_posesinitialize_poses = True
422  topic_suffix = next_topic.split("/")[-1]
423  if topic_suffix in self.initial_posesinitial_poses:
424  self.pre_posepre_pose = PoseStamped(pose=self.initial_posesinitial_poses[topic_suffix])
425  self.initialize_posesinitialize_poses = False
426  return True
427  else:
428  rospy.logdebug(self.initial_posesinitial_poses.keys())
429  rospy.loginfo(
430  "Waiting for pose topic of '%s' to be initialized", topic_suffix
431  )
432  rospy.sleep(1)
433  finally:
434  self.marker_lockmarker_lock.release()
435 
436  def joyCB(self, msg):
437  axes_amount = len(msg.axes)
438  buttons_amount = len(msg.buttons)
439  if axes_amount == 27 and buttons_amount == 19:
440  status = PS3WiredStatus(msg)
441  elif axes_amount == 8 and buttons_amount == 11:
442  status = XBoxStatus(msg)
443  elif axes_amount == 20 and buttons_amount == 17:
444  status = PS3Status(msg)
445  elif axes_amount == 14 and buttons_amount == 14:
446  status = PS4Status(msg)
447  elif axes_amount == 8 and buttons_amount == 13:
448  status = PS4WiredStatus(msg)
449  elif axes_amount == 6 and buttons_amount == 17:
450  status = PS3DualShockStatus(msg)
451  else:
452  raise Exception(
453  "Unknown joystick, axes: {}, buttons: {}".format(
454  axes_amount, buttons_amount
455  )
456  )
457  self.runrun(status)
458  self.historyhistory.add(status)
459 
460  def computePoseFromJoy(self, pre_pose, status):
461  new_pose = PoseStamped()
462  new_pose.header.frame_id = self.frame_idframe_id
463  new_pose.header.stamp = rospy.Time(0.0)
464  # move in local
465  dist = (
466  status.left_analog_y * status.left_analog_y
467  + status.left_analog_x * status.left_analog_x
468  )
469  scale = 200.0
470  x_diff = signedSquare(status.left_analog_y) / scale
471  y_diff = signedSquare(status.left_analog_x) / scale
472  # z
473  if status.L2:
474  z_diff = 0.005
475  elif status.R2:
476  z_diff = -0.005
477  else:
478  z_diff = 0.0
479  if self.historyhistory.all(lambda s: s.L2) or self.historyhistory.all(lambda s: s.R2):
480  z_scale = 4.0
481  else:
482  z_scale = 2.0
483  local_move = numpy.array((x_diff, y_diff, z_diff * z_scale, 1.0))
484  q = numpy.array(
485  (
486  pre_pose.pose.orientation.x,
487  pre_pose.pose.orientation.y,
488  pre_pose.pose.orientation.z,
489  pre_pose.pose.orientation.w,
490  )
491  )
492  xyz_move = numpy.dot(tf.transformations.quaternion_matrix(q), local_move)
493  new_pose.pose.position.x = pre_pose.pose.position.x + xyz_move[0]
494  new_pose.pose.position.y = pre_pose.pose.position.y + xyz_move[1]
495  new_pose.pose.position.z = pre_pose.pose.position.z + xyz_move[2]
496  roll = 0.0
497  pitch = 0.0
498  yaw = 0.0
499  DTHETA = 0.005
500  if status.L1:
501  if self.historyhistory.all(lambda s: s.L1):
502  yaw = yaw + DTHETA * 2
503  else:
504  yaw = yaw + DTHETA
505  elif status.R1:
506  if self.historyhistory.all(lambda s: s.R1):
507  yaw = yaw - DTHETA * 2
508  else:
509  yaw = yaw - DTHETA
510  if status.up:
511  if self.historyhistory.all(lambda s: s.up):
512  pitch = pitch + DTHETA * 2
513  else:
514  pitch = pitch + DTHETA
515  elif status.down:
516  if self.historyhistory.all(lambda s: s.down):
517  pitch = pitch - DTHETA * 2
518  else:
519  pitch = pitch - DTHETA
520  if status.right:
521  if self.historyhistory.all(lambda s: s.right):
522  roll = roll + DTHETA * 2
523  else:
524  roll = roll + DTHETA
525  elif status.left:
526  if self.historyhistory.all(lambda s: s.left):
527  roll = roll - DTHETA * 2
528  else:
529  roll = roll - DTHETA
530  diff_q = tf.transformations.quaternion_from_euler(roll, pitch, yaw)
531  new_q = tf.transformations.quaternion_multiply(q, diff_q)
532  new_pose.pose.orientation.x = new_q[0]
533  new_pose.pose.orientation.y = new_q[1]
534  new_pose.pose.orientation.z = new_q[2]
535  new_pose.pose.orientation.w = new_q[3]
536  return new_pose
537 
538  def run(self, status):
539  if not self.initializedinitialized:
540  # when not initialized, we will force to change planning_group
541  while True:
542  self.updatePlanningGroupupdatePlanningGroup(self.current_planning_group_indexcurrent_planning_group_index)
543  planning_group = self.planning_groups_keysplanning_groups_keys[
544  self.current_planning_group_indexcurrent_planning_group_index
545  ]
546  topics = self.planning_groupsplanning_groups[planning_group]
547  next_topic = topics[self.current_eef_indexcurrent_eef_index]
548  if not self.waitForInitialPosewaitForInitialPose(next_topic, timeout=3):
549  rospy.logwarn(
550  "Unable to initialize planning group "
551  + planning_group
552  + ". Trying different group."
553  )
554  rospy.logwarn(
555  "Is 'Allow External Comm.' enabled in Rviz? Is the 'Query Goal State' robot enabled?"
556  )
557  else:
558  rospy.loginfo("Initialized planning group")
559  self.initializedinitialized = True
560  self.updatePoseTopicupdatePoseTopic(self.current_eef_indexcurrent_eef_index)
561  return
562  # Try to initialize with different planning group
563  self.current_planning_group_indexcurrent_planning_group_index += 1
564  if self.current_planning_group_indexcurrent_planning_group_index >= len(self.planning_groups_keysplanning_groups_keys):
565  self.current_planning_group_indexcurrent_planning_group_index = 0 # reset loop
566  if self.historyhistory.new(status, "select"): # increment planning group
567  self.updatePlanningGroupupdatePlanningGroup(self.current_planning_group_indexcurrent_planning_group_index + 1)
568  self.current_eef_indexcurrent_eef_index = 0 # force to reset
569  self.updatePoseTopicupdatePoseTopic(self.current_eef_indexcurrent_eef_index)
570  return
571  elif self.historyhistory.new(status, "start"): # decrement planning group
572  self.updatePlanningGroupupdatePlanningGroup(self.current_planning_group_indexcurrent_planning_group_index - 1)
573  self.current_eef_indexcurrent_eef_index = 0 # force to reset
574  self.updatePoseTopicupdatePoseTopic(self.current_eef_indexcurrent_eef_index)
575  return
576  elif self.historyhistory.new(status, "triangle"):
577  self.updatePoseTopicupdatePoseTopic(self.current_eef_indexcurrent_eef_index + 1)
578  return
579  elif self.historyhistory.new(status, "cross"):
580  self.updatePoseTopicupdatePoseTopic(self.current_eef_indexcurrent_eef_index - 1)
581  return
582  elif self.historyhistory.new(status, "square"): # plan
583  rospy.loginfo("Plan")
584  self.plan_pubplan_pub.publish(Empty())
585  return
586  elif self.historyhistory.new(status, "circle"): # execute
587  rospy.loginfo("Execute")
588  self.execute_pubexecute_pub.publish(Empty())
589  return
590  self.marker_lockmarker_lock.acquire()
591  pre_pose = self.pre_posepre_pose
592  new_pose = self.computePoseFromJoycomputePoseFromJoy(pre_pose, status)
593  now = rospy.Time.from_sec(time.time())
594  # placement.time_from_start = now - self.prev_time
595  if (now - self.prev_timeprev_time).to_sec() > 1 / 30.0:
596  # rospy.loginfo(new_pose)
597  self.pose_pubpose_pub.publish(new_pose)
598  self.joy_pose_pubjoy_pose_pub.publish(new_pose)
599  self.prev_timeprev_time = now
600  # sync start state to the real robot state
601  self.countercounter = self.countercounter + 1
602  if self.countercounter % 10:
603  self.update_start_state_pubupdate_start_state_pub.publish(Empty())
604  self.pre_posepre_pose = new_pose
605  self.marker_lockmarker_lock.release()
606  # update self.initial_poses
607  self.marker_lockmarker_lock.acquire()
608  self.initial_posesinitial_poses[self.current_pose_topiccurrent_pose_topic.split("/")[-1]] = new_pose.pose
609  self.marker_lockmarker_lock.release()
def updatePoseTopic(self, next_index, wait=True)
def waitForInitialPose(self, next_topic, timeout=None)
string release
Definition: conf.py:29
std::string append(const std::string &left, const std::string &right)
void print(PropagationDistanceField &pdf, int numX, int numY, int numZ)