40 from __future__ 
import print_function
    42 import xml.dom.minidom
    43 from operator 
import add
    46 from moveit_ros_planning_interface._moveit_robot_interface 
import RobotInterface
    53 from std_msgs.msg 
import Empty, String
    54 from sensor_msgs.msg 
import Joy
    55 from geometry_msgs.msg 
import PoseStamped
    56 from visualization_msgs.msg 
import InteractiveMarkerInit
    63   return val * val * sign
    94         JoyStatus.__init__(self)
    95         if msg.buttons[8] == 1:
    99         if msg.buttons[6] == 1:
   103         if msg.buttons[7] == 1:
   107         if msg.buttons[9] == 1:
   111         if msg.buttons[10] == 1:
   115         if msg.buttons[2] == 1:
   119         if msg.buttons[1] == 1:
   123         if msg.axes[7] > 0.1:
   127         if msg.axes[7] < -0.1:
   131         if msg.axes[6] > 0.1:
   135         if msg.axes[6] < -0.1:
   139         if msg.buttons[3] == 1:
   143         if msg.buttons[0] == 1:
   147         if msg.buttons[4] == 1:
   151         if msg.buttons[5] == 1:
   155         if msg.axes[2] < -0.5:
   159         if msg.axes[5] < -0.5:
   171         JoyStatus.__init__(self)
   173         if msg.buttons[16] == 1:
   177         if msg.buttons[0] == 1:
   181         if msg.buttons[3] == 1:
   185         if msg.buttons[1] == 1:
   189         if msg.buttons[2] == 1:
   249         JoyStatus.__init__(self)
   251         if msg.buttons[16] == 1:
   255         if msg.buttons[0] == 1:
   259         if msg.buttons[3] == 1:
   263         if msg.buttons[1] == 1:
   267         if msg.buttons[2] == 1:
   271         if msg.buttons[15] == 1:
   275         if msg.buttons[4] == 1:
   279         if msg.buttons[6] == 1:
   283         if msg.buttons[7] == 1:
   287         if msg.buttons[5] == 1:
   291         if msg.buttons[12] == 1:
   295         if msg.buttons[14] == 1:
   299         if msg.buttons[13] == 1:
   303         if msg.buttons[10] == 1:
   307         if msg.buttons[11] == 1:
   311         if msg.buttons[8] == 1:
   315         if msg.buttons[9] == 1:
   330     self.buffer.append(status)
   334     for status 
in self.
buffer:
   345   def new(self, status, attr):
   347       return getattr(status, attr)
   349       return getattr(status, attr) 
and not getattr(self.
latest(), attr)
   353         ri = RobotInterface(
"/robot_description")
   355         for g 
in ri.get_group_names():
   357             planning_groups[g] = [
"/rviz/moveit/move_marker/goal_" + l
   359         for name 
in planning_groups.keys():
   360             if len(planning_groups[name]) == 0:
   361                 del planning_groups[name]
   363                 print(name, planning_groups[name])
   376         self.pre_pose.pose.orientation.w = 1
   382         self.
plan_group_pub = rospy.Publisher(
'/rviz/moveit/select_planning_group', String, queue_size=5)
   385         self.
joy_pose_pub = rospy.Publisher(
"/joy_pose", PoseStamped, queue_size=1)
   386         self.
plan_pub = rospy.Publisher(
"/rviz/moveit/plan", Empty, queue_size=5)
   387         self.
execute_pub = rospy.Publisher(
"/rviz/moveit/execute", Empty, queue_size=5)
   390         self.
interactive_marker_sub = rospy.Subscriber(
"/rviz_moveit_motion_planning_display/robot_interaction_interactive_marker_topic/update_full",
   391                                                        InteractiveMarkerInit,
   393         self.
sub = rospy.Subscriber(
"/joy", Joy, self.
joyCB, queue_size=1)
   401         next_planning_group = 
None   405             msg = 
'Check if you started movegroups. Exiting.'   407             raise rospy.ROSInitException(msg)
   408         rospy.loginfo(
"Changed planning group to " + next_planning_group)
   409         self.plan_group_pub.publish(next_planning_group)
   413         if next_index >= len(topics):
   422         self.
pose_pub = rospy.Publisher(next_topic, PoseStamped, queue_size=5)
   428             self.marker_lock.acquire()
   432             for marker 
in msg.markers:
   433                 if marker.name.startswith(
"EE:goal_"):
   435                     if marker.header.frame_id != self.
frame_id:
   436                         ps = PoseStamped(header=marker.header, pose=marker.pose)
   438                             transformed_pose = self.tf_listener.transformPose(self.
frame_id, ps)
   441                             rospy.logerr(
"tf error when resolving tf: %s" % e)
   445             self.marker_lock.release()
   448         while not rospy.is_shutdown():
   449             counter = counter + 1
   450             if timeout 
and counter >= timeout:
   453                 self.marker_lock.acquire()
   455                 topic_suffix = next_topic.split(
"/")[-1]
   456                 if self.initial_poses.has_key(topic_suffix):
   461                     rospy.logdebug(self.initial_poses.keys())
   462                     rospy.loginfo(
"Waiting for pose topic of '%s' to be initialized",
   466                 self.marker_lock.release()
   468         if len(msg.axes) == 27 
and len(msg.buttons) == 19:
   470         elif len(msg.axes) == 8 
and len(msg.buttons) == 11:
   472         elif len(msg.axes) == 20 
and len(msg.buttons) == 17:
   475             raise Exception(
"Unknown joystick")
   477         self.history.add(status)
   479         new_pose = PoseStamped()
   480         new_pose.header.frame_id = self.
frame_id   481         new_pose.header.stamp = rospy.Time(0.0)
   483         dist = status.left_analog_y * status.left_analog_y + status.left_analog_x * status.left_analog_x
   494         if self.history.all(
lambda s: s.L2) 
or self.history.all(
lambda s: s.R2):
   498         local_move = numpy.array((x_diff, y_diff,
   501         q = numpy.array((pre_pose.pose.orientation.x,
   502                          pre_pose.pose.orientation.y,
   503                          pre_pose.pose.orientation.z,
   504                          pre_pose.pose.orientation.w))
   505         xyz_move = numpy.dot(tf.transformations.quaternion_matrix(q),
   507         new_pose.pose.position.x = pre_pose.pose.position.x + xyz_move[0]
   508         new_pose.pose.position.y = pre_pose.pose.position.y + xyz_move[1]
   509         new_pose.pose.position.z = pre_pose.pose.position.z + xyz_move[2]
   515             if self.history.all(
lambda s: s.L1):
   516                 yaw = yaw + DTHETA * 2
   520             if self.history.all(
lambda s: s.R1):
   521                 yaw = yaw - DTHETA * 2
   525             if self.history.all(
lambda s: s.up):
   526                 pitch = pitch + DTHETA * 2
   528                 pitch = pitch + DTHETA
   530             if self.history.all(
lambda s: s.down):
   531                 pitch = pitch - DTHETA * 2
   533                 pitch = pitch - DTHETA
   535             if self.history.all(
lambda s: s.right):
   536                 roll = roll + DTHETA * 2
   540             if self.history.all(
lambda s: s.left):
   541                 roll = roll - DTHETA * 2
   544         diff_q = tf.transformations.quaternion_from_euler(roll, pitch, yaw)
   545         new_q = tf.transformations.quaternion_multiply(q, diff_q)
   546         new_pose.pose.orientation.x = new_q[0]
   547         new_pose.pose.orientation.y = new_q[1]
   548         new_pose.pose.orientation.z = new_q[2]
   549         new_pose.pose.orientation.w = new_q[3]
   560                     rospy.logwarn(
"Unable to initialize planning group " + planning_group + 
". Trying different group.")
   561                     rospy.logwarn(
"Is 'Allow External Comm.' enabled in Rviz? Is the 'Query Goal State' robot enabled?")
   563                     rospy.loginfo(
"Initialized planning group")
   571         if self.history.new(status, 
"select"):   
   576         elif self.history.new(status, 
"start"):   
   581         elif self.history.new(status, 
"triangle"):
   584         elif self.history.new(status, 
"cross"):
   587         elif self.history.new(status, 
"square"):   
   588             rospy.loginfo(
"Plan")
   589             self.plan_pub.publish(Empty())
   591         elif self.history.new(status, 
"circle"):   
   592             rospy.loginfo(
"Execute")
   593             self.execute_pub.publish(Empty())
   595         self.marker_lock.acquire()
   598         now = rospy.Time.from_sec(time.time())
   600         if (now - self.
prev_time).to_sec() > 1 / 30.0:
   602             self.pose_pub.publish(new_pose)
   603             self.joy_pose_pub.publish(new_pose)
   608             self.update_start_state_pub.publish(Empty())
   610         self.marker_lock.release()
   612         self.marker_lock.acquire()
   613         self.
initial_poses[self.current_pose_topic.split(
"/")[-1]] = new_pose.pose
   614         self.marker_lock.release()
 
def updatePoseTopic(self, next_index, wait=True)
def waitForInitialPose(self, next_topic, timeout=None)
def computePoseFromJoy(self, pre_pose, status)
def updatePlanningGroup(self, next_index)
def new(self, status, attr)
def __init__(self, max_length=10)
current_planning_group_index