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 import xml.dom.minidom
00041 from operator import add
00042 import sys
00043 import threading
00044 from moveit_ros_planning_interface._moveit_robot_interface import RobotInterface
00045
00046 import rospy
00047 import roslib
00048 import numpy
00049 import time
00050 import tf
00051 from std_msgs.msg import Empty, String
00052 from sensor_msgs.msg import Joy
00053 from geometry_msgs.msg import PoseStamped
00054 from visualization_msgs.msg import InteractiveMarkerInit
00055
00056 def signedSquare(val):
00057 if val > 0:
00058 sign = 1
00059 else:
00060 sign = -1
00061 return val * val * sign
00062
00063
00064
00065
00066 class JoyStatus():
00067 def __init__(self):
00068 self.center = False
00069 self.select = False
00070 self.start = False
00071 self.L3 = False
00072 self.R3 = False
00073 self.square = False
00074 self.up = False
00075 self.down = False
00076 self.left = False
00077 self.right = False
00078 self.triangle = False
00079 self.cross = False
00080 self.circle = False
00081 self.L1 = False
00082 self.R1 = False
00083 self.L2 = False
00084 self.R2 = False
00085 self.left_analog_x = 0.0
00086 self.left_analog_y = 0.0
00087 self.right_analog_x = 0.0
00088 self.right_analog_y = 0.0
00089
00090 class XBoxStatus(JoyStatus):
00091 def __init__(self, msg):
00092 JoyStatus.__init__(self)
00093 if msg.buttons[8] == 1:
00094 self.center = True
00095 else:
00096 self.center = False
00097 if msg.buttons[6] == 1:
00098 self.select = True
00099 else:
00100 self.select = False
00101 if msg.buttons[7] == 1:
00102 self.start = True
00103 else:
00104 self.start = False
00105 if msg.buttons[9] == 1:
00106 self.L3 = True
00107 else:
00108 self.L3 = False
00109 if msg.buttons[10] == 1:
00110 self.R3 = True
00111 else:
00112 self.R3 = False
00113 if msg.buttons[2] == 1:
00114 self.square = True
00115 else:
00116 self.square = False
00117 if msg.buttons[1] == 1:
00118 self.circle = True
00119 else:
00120 self.circle = False
00121 if msg.axes[7] > 0.1:
00122 self.up = True
00123 else:
00124 self.up = False
00125 if msg.axes[7] < -0.1:
00126 self.down = True
00127 else:
00128 self.down = False
00129 if msg.axes[6] > 0.1:
00130 self.left = True
00131 else:
00132 self.left = False
00133 if msg.axes[6] < -0.1:
00134 self.right = True
00135 else:
00136 self.right = False
00137 if msg.buttons[3] == 1:
00138 self.triangle = True
00139 else:
00140 self.triangle = False
00141 if msg.buttons[0] == 1:
00142 self.cross = True
00143 else:
00144 self.cross = False
00145 if msg.buttons[4] == 1:
00146 self.L1 = True
00147 else:
00148 self.L1 = False
00149 if msg.buttons[5] == 1:
00150 self.R1 = True
00151 else:
00152 self.R1 = False
00153 if msg.axes[2] < -0.5:
00154 self.L2 = True
00155 else:
00156 self.L2 = False
00157 if msg.axes[5] < -0.5:
00158 self.R2 = True
00159 else:
00160 self.R2 = False
00161 self.left_analog_x = msg.axes[0]
00162 self.left_analog_y = msg.axes[1]
00163 self.right_analog_x = msg.axes[3]
00164 self.right_analog_y = msg.axes[4]
00165 self.orig_msg = msg
00166
00167 class PS3Status(JoyStatus):
00168 def __init__(self, msg):
00169 JoyStatus.__init__(self)
00170
00171 if msg.buttons[16] == 1:
00172 self.center = True
00173 else:
00174 self.center = False
00175 if msg.buttons[0] == 1:
00176 self.select = True
00177 else:
00178 self.select = False
00179 if msg.buttons[3] == 1:
00180 self.start = True
00181 else:
00182 self.start = False
00183 if msg.buttons[1] == 1:
00184 self.L3 = True
00185 else:
00186 self.L3 = False
00187 if msg.buttons[2] == 1:
00188 self.R3 = True
00189 else:
00190 self.R3 = False
00191 if msg.axes[15] < 0:
00192 self.square = True
00193 else:
00194 self.square = False
00195 if msg.axes[4] < 0:
00196 self.up = True
00197 else:
00198 self.up = False
00199 if msg.axes[6] < 0:
00200 self.down = True
00201 else:
00202 self.down = False
00203 if msg.axes[7] < 0:
00204 self.left = True
00205 else:
00206 self.left = False
00207 if msg.axes[5] < 0:
00208 self.right = True
00209 else:
00210 self.right = False
00211 if msg.axes[12] < 0:
00212 self.triangle = True
00213 else:
00214 self.triangle = False
00215 if msg.axes[14] < 0:
00216 self.cross = True
00217 else:
00218 self.cross = False
00219 if msg.axes[13] < 0:
00220 self.circle = True
00221 else:
00222 self.circle = False
00223 if msg.axes[10] < 0:
00224 self.L1 = True
00225 else:
00226 self.L1 = False
00227 if msg.axes[11] < 0:
00228 self.R1 = True
00229 else:
00230 self.R1 = False
00231 if msg.axes[8] < 0:
00232 self.L2 = True
00233 else:
00234 self.L2 = False
00235 if msg.axes[9] < 0:
00236 self.R2 = True
00237 else:
00238 self.R2 = False
00239 self.left_analog_x = msg.axes[0]
00240 self.left_analog_y = msg.axes[1]
00241 self.right_analog_x = msg.axes[2]
00242 self.right_analog_y = msg.axes[3]
00243 self.orig_msg = msg
00244
00245 class PS3WiredStatus(JoyStatus):
00246 def __init__(self, msg):
00247 JoyStatus.__init__(self)
00248
00249 if msg.buttons[16] == 1:
00250 self.center = True
00251 else:
00252 self.center = False
00253 if msg.buttons[0] == 1:
00254 self.select = True
00255 else:
00256 self.select = False
00257 if msg.buttons[3] == 1:
00258 self.start = True
00259 else:
00260 self.start = False
00261 if msg.buttons[1] == 1:
00262 self.L3 = True
00263 else:
00264 self.L3 = False
00265 if msg.buttons[2] == 1:
00266 self.R3 = True
00267 else:
00268 self.R3 = False
00269 if msg.buttons[15] == 1:
00270 self.square = True
00271 else:
00272 self.square = False
00273 if msg.buttons[4] == 1:
00274 self.up = True
00275 else:
00276 self.up = False
00277 if msg.buttons[6] == 1:
00278 self.down = True
00279 else:
00280 self.down = False
00281 if msg.buttons[7] == 1:
00282 self.left = True
00283 else:
00284 self.left = False
00285 if msg.buttons[5] == 1:
00286 self.right = True
00287 else:
00288 self.right = False
00289 if msg.buttons[12] == 1:
00290 self.triangle = True
00291 else:
00292 self.triangle = False
00293 if msg.buttons[14] == 1:
00294 self.cross = True
00295 else:
00296 self.cross = False
00297 if msg.buttons[13] == 1:
00298 self.circle = True
00299 else:
00300 self.circle = False
00301 if msg.buttons[10] == 1:
00302 self.L1 = True
00303 else:
00304 self.L1 = False
00305 if msg.buttons[11] == 1:
00306 self.R1 = True
00307 else:
00308 self.R1 = False
00309 if msg.buttons[8] == 1:
00310 self.L2 = True
00311 else:
00312 self.L2 = False
00313 if msg.buttons[9] == 1:
00314 self.R2 = True
00315 else:
00316 self.R2 = False
00317 self.left_analog_x = msg.axes[0]
00318 self.left_analog_y = msg.axes[1]
00319 self.right_analog_x = msg.axes[2]
00320 self.right_analog_y = msg.axes[3]
00321 self.orig_msg = msg
00322
00323
00324 class ArcticStatus(JoyStatus):
00325 def __init__(self, msg):
00326 JoyStatus.__init__(self)
00327 if msg.buttons[8] == 1:
00328
00329 self.select = True
00330 else:
00331 self.select = False
00332 if msg.buttons[9] == 1:
00333
00334 self.start = True
00335 else:
00336 self.start = False
00337 if msg.buttons[3] == 1:
00338
00339 self.square = True
00340 else:
00341 self.square = False
00342 if msg.buttons[1] == 1:
00343
00344 self.circle = True
00345 else:
00346 self.circle = False
00347 if msg.axes[5] > 0.1:
00348
00349 self.up = True
00350 else:
00351 self.up = False
00352 if msg.axes[5] < -0.1:
00353
00354 self.down = True
00355 else:
00356 self.down = False
00357 if msg.axes[4] < -0.1:
00358
00359 self.left = True
00360 else:
00361 self.left = False
00362 if msg.axes[4] > 0.1:
00363
00364 self.right = True
00365 else:
00366 self.right = False
00367 if msg.buttons[0] == 1:
00368
00369 self.triangle = True
00370 else:
00371 self.triangle = False
00372 if msg.buttons[2] == 1:
00373
00374 self.cross = True
00375 else:
00376 self.cross = False
00377 if msg.buttons[4] == 1:
00378 self.L1 = True
00379 else:
00380 self.L1 = False
00381 if msg.buttons[5] == 1:
00382 self.R1 = True
00383 else:
00384 self.R1 = False
00385 if msg.buttons[6] == 1:
00386 self.L2 = True
00387 else:
00388 self.L2 = False
00389 if msg.buttons[7] == 1:
00390 self.R2 = True
00391 else:
00392 self.R2 = False
00393 self.left_analog_x = msg.axes[0]
00394 self.left_analog_y = msg.axes[1]
00395 self.right_analog_x = msg.axes[2]
00396 self.right_analog_y = msg.axes[3]
00397 self.orig_msg = msg
00398
00399 class StatusHistory():
00400 def __init__(self, max_length=10):
00401 self.max_length = max_length
00402 self.buffer = []
00403 def add(self, status):
00404 self.buffer.append(status)
00405 if len(self.buffer) > self.max_length:
00406 self.buffer = self.buffer[1:self.max_length+1]
00407 def all(self, proc):
00408 for status in self.buffer:
00409 if not proc(status):
00410 return False
00411 return True
00412 def latest(self):
00413 if len(self.buffer) > 0:
00414 return self.buffer[-1]
00415 else:
00416 return None
00417 def length(self):
00418 return len(self.buffer)
00419 def new(self, status, attr):
00420 if len(self.buffer) == 0:
00421 return getattr(status, attr)
00422 else:
00423 return getattr(status, attr) and not getattr(self.latest(), attr)
00424
00425 class MoveitJoy:
00426 def parseSRDF(self):
00427 ri = RobotInterface("/robot_description")
00428 planning_groups = {}
00429 for g in ri.get_group_names():
00430 self.planning_groups_tips[g] = ri.get_group_joint_tips(g)
00431 planning_groups[g] = ["/rviz/moveit/move_marker/goal_" + l
00432 for l in self.planning_groups_tips[g]]
00433 for name in planning_groups.keys():
00434 if len(planning_groups[name]) == 0:
00435 del planning_groups[name]
00436 else:
00437 print name, planning_groups[name]
00438 self.planning_groups = planning_groups
00439 self.planning_groups_keys = planning_groups.keys()
00440 self.frame_id = ri.get_planning_frame()
00441 def __init__(self):
00442 self.initial_poses = {}
00443 self.planning_groups_tips = {}
00444 self.tf_listener = tf.TransformListener()
00445 self.marker_lock = threading.Lock()
00446 self.prev_time = rospy.Time.now()
00447 self.counter = 0
00448 self.history = StatusHistory(max_length=10)
00449 self.pre_pose = PoseStamped()
00450 self.pre_pose.pose.orientation.w = 1
00451 self.current_planning_group_index = 0
00452 self.current_eef_index = 0
00453 self.initialize_poses = False
00454 self.initialized = False
00455 self.parseSRDF()
00456 self.plan_group_pub = rospy.Publisher('/rviz/moveit/select_planning_group', String, queue_size=5)
00457 self.updatePlanningGroup(0)
00458 self.updatePoseTopic(0, False)
00459 self.joy_pose_pub = rospy.Publisher("/joy_pose", PoseStamped, queue_size=1)
00460 self.plan_pub = rospy.Publisher("/rviz/moveit/plan", Empty, queue_size=5)
00461 self.execute_pub = rospy.Publisher("/rviz/moveit/execute", Empty, queue_size=5)
00462 self.update_start_state_pub = rospy.Publisher("/rviz/moveit/update_start_state", Empty, queue_size=5)
00463 self.update_goal_state_pub = rospy.Publisher("/rviz/moveit/update_goal_state", Empty, queue_size=5)
00464 self.interactive_marker_sub = rospy.Subscriber("/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/update_full",
00465 InteractiveMarkerInit,
00466 self.markerCB, queue_size=1)
00467 self.sub = rospy.Subscriber("/joy", Joy, self.joyCB, queue_size=1)
00468 def updatePlanningGroup(self, next_index):
00469 if next_index >= len(self.planning_groups_keys):
00470 self.current_planning_group_index = 0
00471 elif next_index < 0:
00472 self.current_planning_group_index = len(self.planning_groups_keys) - 1
00473 else:
00474 self.current_planning_group_index = next_index
00475 next_planning_group = None
00476 try:
00477 next_planning_group = self.planning_groups_keys[self.current_planning_group_index]
00478 except IndexError:
00479 msg = 'Check if you started movegroups. Exiting.'
00480 rospy.logfatal(msg)
00481 raise rospy.ROSInitException(msg)
00482 rospy.loginfo("Changed planning group to " + next_planning_group)
00483 self.plan_group_pub.publish(next_planning_group)
00484 def updatePoseTopic(self, next_index, wait=True):
00485 planning_group = self.planning_groups_keys[self.current_planning_group_index]
00486 topics = self.planning_groups[planning_group]
00487 if next_index >= len(topics):
00488 self.current_eef_index = 0
00489 elif next_index < 0:
00490 self.current_eef_index = len(topics) - 1
00491 else:
00492 self.current_eef_index = next_index
00493 next_topic = topics[self.current_eef_index]
00494
00495 rospy.loginfo("Changed controlled end effector to " + self.planning_groups_tips[planning_group][self.current_eef_index])
00496 self.pose_pub = rospy.Publisher(next_topic, PoseStamped, queue_size=5)
00497 if wait:
00498 self.waitForInitialPose(next_topic)
00499 self.current_pose_topic = next_topic
00500 def markerCB(self, msg):
00501 try:
00502 self.marker_lock.acquire()
00503 if not self.initialize_poses:
00504 return
00505 self.initial_poses = {}
00506 for marker in msg.markers:
00507 if marker.name.startswith("EE:goal_"):
00508
00509 if marker.header.frame_id != self.frame_id:
00510 ps = PoseStamped(header=marker.header, pose=marker.pose)
00511 try:
00512 transformed_pose = self.tf_listener.transformPose(self.frame_id, ps)
00513 self.initial_poses[marker.name[3:]] = transformed_pose.pose
00514 except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException, e):
00515 rospy.logerr("tf error when resolving tf: %s" % e)
00516 else:
00517 self.initial_poses[marker.name[3:]] = marker.pose
00518 finally:
00519 self.marker_lock.release()
00520 def waitForInitialPose(self, next_topic, timeout=None):
00521 counter = 0
00522 while not rospy.is_shutdown():
00523 counter = counter + 1
00524 if timeout and counter >= timeout:
00525 return False
00526 try:
00527 self.marker_lock.acquire()
00528 self.initialize_poses = True
00529 topic_suffix = next_topic.split("/")[-1]
00530 if self.initial_poses.has_key(topic_suffix):
00531 self.pre_pose = PoseStamped(pose=self.initial_poses[topic_suffix])
00532 self.initialize_poses = False
00533 return True
00534 else:
00535 rospy.logdebug(self.initial_poses.keys())
00536 rospy.loginfo("Waiting for pose topic of '%s' to be initialized",
00537 topic_suffix)
00538 rospy.sleep(1)
00539 finally:
00540 self.marker_lock.release()
00541 def joyCB(self, msg):
00542 if len(msg.axes) == 27 and len(msg.buttons) == 19:
00543 status = PS3WiredStatus(msg)
00544 elif len(msg.axes) == 8 and len(msg.buttons) == 11:
00545 status = XBoxStatus(msg)
00546 elif len(msg.axes) == 20 and len(msg.buttons) == 17:
00547 status = PS3Status(msg)
00548 elif len(msg.axes) == 7 and len(msg.buttons) == 12:
00549 status = ArcticStatus(msg)
00550 else:
00551 raise Exception("Unknown joystick")
00552 self.run(status)
00553 self.history.add(status)
00554 def computePoseFromJoy(self, pre_pose, status):
00555 new_pose = PoseStamped()
00556 new_pose.header.frame_id = self.frame_id
00557 new_pose.header.stamp = rospy.Time(0.0)
00558
00559 dist = status.left_analog_y * status.left_analog_y + status.left_analog_x * status.left_analog_x
00560 scale = 200.0
00561 x_diff = signedSquare(status.left_analog_y) / scale
00562 y_diff = signedSquare(status.left_analog_x) / scale
00563
00564 if status.L2:
00565 z_diff = 0.005
00566 elif status.R2:
00567 z_diff = -0.005
00568 else:
00569 z_diff = 0.0
00570 if self.history.all(lambda s: s.L2) or self.history.all(lambda s: s.R2):
00571 z_scale = 4.0
00572 else:
00573 z_scale = 2.0
00574 local_move = numpy.array((x_diff, y_diff,
00575 z_diff * z_scale,
00576 1.0))
00577 q = numpy.array((pre_pose.pose.orientation.x,
00578 pre_pose.pose.orientation.y,
00579 pre_pose.pose.orientation.z,
00580 pre_pose.pose.orientation.w))
00581 xyz_move = numpy.dot(tf.transformations.quaternion_matrix(q),
00582 local_move)
00583 new_pose.pose.position.x = pre_pose.pose.position.x + xyz_move[0]
00584 new_pose.pose.position.y = pre_pose.pose.position.y + xyz_move[1]
00585 new_pose.pose.position.z = pre_pose.pose.position.z + xyz_move[2]
00586 roll = 0.0
00587 pitch = 0.0
00588 yaw = 0.0
00589 DTHETA = 0.005
00590 if status.L1:
00591 if self.history.all(lambda s: s.L1):
00592 yaw = yaw + DTHETA * 2
00593 else:
00594 yaw = yaw + DTHETA
00595 elif status.R1:
00596 if self.history.all(lambda s: s.R1):
00597 yaw = yaw - DTHETA * 2
00598 else:
00599 yaw = yaw - DTHETA
00600 if status.up:
00601 if self.history.all(lambda s: s.up):
00602 pitch = pitch + DTHETA * 2
00603 else:
00604 pitch = pitch + DTHETA
00605 elif status.down:
00606 if self.history.all(lambda s: s.down):
00607 pitch = pitch - DTHETA * 2
00608 else:
00609 pitch = pitch - DTHETA
00610 if status.right:
00611 if self.history.all(lambda s: s.right):
00612 roll = roll + DTHETA * 2
00613 else:
00614 roll = roll + DTHETA
00615 elif status.left:
00616 if self.history.all(lambda s: s.left):
00617 roll = roll - DTHETA * 2
00618 else:
00619 roll = roll - DTHETA
00620 diff_q = tf.transformations.quaternion_from_euler(roll, pitch, yaw)
00621 new_q = tf.transformations.quaternion_multiply(q, diff_q)
00622 new_pose.pose.orientation.x = new_q[0]
00623 new_pose.pose.orientation.y = new_q[1]
00624 new_pose.pose.orientation.z = new_q[2]
00625 new_pose.pose.orientation.w = new_q[3]
00626 return new_pose
00627 def run(self, status):
00628 if not self.initialized:
00629
00630 while True:
00631 self.updatePlanningGroup(self.current_planning_group_index)
00632 planning_group = self.planning_groups_keys[self.current_planning_group_index]
00633 topics = self.planning_groups[planning_group]
00634 next_topic = topics[self.current_eef_index]
00635 if not self.waitForInitialPose(next_topic, timeout=3):
00636 rospy.logwarn("Unable to initialize planning group " + planning_group + ". Trying different group.")
00637 rospy.logwarn("Is 'Allow External Comm.' enabled in Rviz? Is the 'Query Goal State' robot enabled?")
00638 else:
00639 rospy.loginfo("Initialized planning group")
00640 self.initialized = True
00641 self.updatePoseTopic(self.current_eef_index)
00642 return
00643
00644 self.current_planning_group_index += 1
00645 if self.current_planning_group_index >= len(self.planning_groups_keys):
00646 self.current_planning_group_index = 0
00647 if self.history.new(status, "select"):
00648 self.updatePlanningGroup(self.current_planning_group_index + 1)
00649 self.current_eef_index = 0
00650 self.updatePoseTopic(self.current_eef_index)
00651 return
00652 elif self.history.new(status, "start"):
00653 self.updatePlanningGroup(self.current_planning_group_index - 1)
00654 self.current_eef_index = 0
00655 self.updatePoseTopic(self.current_eef_index)
00656 return
00657 elif self.history.new(status, "triangle"):
00658 self.updatePoseTopic(self.current_eef_index + 1)
00659 return
00660 elif self.history.new(status, "cross"):
00661 self.updatePoseTopic(self.current_eef_index - 1)
00662 return
00663 elif self.history.new(status, "square"):
00664 rospy.loginfo("Plan")
00665 self.plan_pub.publish(Empty())
00666 return
00667 elif self.history.new(status, "circle"):
00668 rospy.loginfo("Execute")
00669 self.execute_pub.publish(Empty())
00670 return
00671 self.marker_lock.acquire()
00672 pre_pose = self.pre_pose
00673 new_pose = self.computePoseFromJoy(pre_pose, status)
00674 now = rospy.Time.from_sec(time.time())
00675
00676 if (now - self.prev_time).to_sec() > 1 / 30.0:
00677
00678 self.pose_pub.publish(new_pose)
00679 self.joy_pose_pub.publish(new_pose)
00680 self.prev_time = now
00681
00682 self.counter = self.counter + 1
00683 if self.counter % 10:
00684 self.update_start_state_pub.publish(Empty())
00685 self.pre_pose = new_pose
00686 self.marker_lock.release()
00687
00688 self.marker_lock.acquire()
00689 self.initial_poses[self.current_pose_topic.split("/")[-1]] = new_pose.pose
00690 self.marker_lock.release()