00001 import rospy
00002
00003 import imp
00004 try:
00005 imp.find_module("actionlib")
00006 except:
00007 import roslib; roslib.load_manifest('jsk_teleop_joy')
00008
00009 import actionlib
00010 from jsk_rviz_plugins.msg import OverlayMenu
00011 from joy_pose_6d import JoyPose6D
00012 from jsk_interactive_marker.srv import GetTransformableMarkerPose
00013 from jsk_interactive_marker.srv import SetPose
00014 from geometry_msgs.msg import PoseStamped
00015 from std_srvs.srv import Empty
00016 import copy
00017 import time
00018 import tf
00019
00020 def isSamePose(pose1, pose2):
00021 return all([getattr(pose1.position, attr) == getattr(pose2.position, attr) for attr in ["x", "y", "z"]]) and all ([getattr(pose1.orientation, attr) == getattr(pose2.orientation, attr) for attr in ["x", "y", "z", "w"]])
00022
00023 class JoyFootstepMarker(JoyPose6D):
00024 '''
00025 Usage:
00026 Refer JoyPose6D
00027 circle: execute footstep
00028 cross: reset marker
00029 triangle: stack footstep (only used in stack mode)
00030 start: toggle footstep marker mode (single -> continuous -> stack)
00031
00032 Args:
00033 use_tf [Boolean, default: True]: update marker pose using tf
00034 publish_pose : forced False
00035 frame_id [String, default: map]: frame_id of publishing pose, this is overwritten by parameter, ~frame_id
00036 pose [String, default: pose]: topic name for publishing pose
00037 set_pose [String, default: set_pose]: topic name for setting pose by topic
00038 '''
00039 def __init__(self, name, args):
00040 args['publish_pose'] = False
00041 JoyPose6D.__init__(self, name, args)
00042 self.pose_pub = rospy.Publisher(self.getArg('pose', 'pose'), PoseStamped)
00043 self.current_goal_pose = None
00044 self.use_tf = self.getArg('use_tf', True)
00045 self.pose_updated = False
00046
00047
00048 self.pub = rospy.Publisher("joy_footstep_menu", OverlayMenu)
00049 self.menu = None
00050
00051
00052 rospy.wait_for_service('/footstep_marker/reset_marker')
00053 self.reset_marker_srv = rospy.ServiceProxy('/footstep_marker/reset_marker', Empty)
00054 rospy.wait_for_service('/footstep_marker/toggle_footstep_marker_mode')
00055 self.toggle_footstep_marker_mode_srv = rospy.ServiceProxy('/footstep_marker/toggle_footstep_marker_mode', Empty)
00056 rospy.wait_for_service('/footstep_marker/execute_footstep')
00057 self.execute_footstep_srv = rospy.ServiceProxy('/footstep_marker/execute_footstep', Empty)
00058 rospy.wait_for_service('/footstep_marker/get_footstep_marker_pose')
00059 self.get_footstep_marker_pose_srv = rospy.ServiceProxy('/footstep_marker/get_footstep_marker_pose', GetTransformableMarkerPose)
00060 rospy.wait_for_service('/footstep_marker/stack_marker_pose')
00061 self.get_stack_marker_pose_srv = rospy.ServiceProxy('/footstep_marker/stack_marker_pose', SetPose)
00062
00063
00064 marker_pose = self.getCurrentMarkerPose("movable_footstep_marker")
00065 if marker_pose != None:
00066 self.pre_pose = marker_pose
00067
00068 def joyCB(self, status, history):
00069 now = rospy.Time.from_sec(time.time())
00070 latest = history.latest()
00071 if not latest:
00072 return
00073
00074
00075 if self.menu != None:
00076 if status.up and not latest.up:
00077 self.menu.current_index = (self.menu.current_index - 1) % len(self.menu.menus)
00078 self.pub.publish(self.menu)
00079 elif status.down and not latest.down:
00080 self.menu.current_index = (self.menu.current_index + 1) % len(self.menu.menus)
00081 self.pub.publish(self.menu)
00082 elif status.circle and not latest.circle:
00083 self.menu.action = OverlayMenu.ACTION_CLOSE
00084 if self.menu.current_index == self.menu.menus.index("Yes"):
00085 try:
00086 self.execute_footstep_srv()
00087 except rospy.ServiceException, e:
00088 rospy.logwarn("Execute Footsteps failed: %s", e)
00089 self.pub.publish(self.menu)
00090 self.menu = None
00091 elif status.cross and not latest.cross:
00092 self.menu.action = OverlayMenu.ACTION_CLOSE
00093 self.pub.publish(self.menu)
00094 self.menu = None
00095 else:
00096 self.pub.publish(self.menu)
00097 return
00098
00099
00100 JoyPose6D.joyCB(self, status, history)
00101 if status.circle and not latest.circle:
00102 self.menu = OverlayMenu()
00103 self.menu.title = "Execute Footsteps?"
00104 self.menu.menus = ["Yes", "No"]
00105 self.menu.current_index = 1
00106 self.pub.publish(self.menu)
00107 elif status.cross and not latest.cross:
00108 self.reset_marker_srv()
00109 marker_pose = self.getCurrentMarkerPose("initial_footstep_marker")
00110 if marker_pose != None:
00111 self.pre_pose = marker_pose
00112 else:
00113 self.pre_pose = PoseStamped()
00114 self.pre_pose.pose.orientation.w = 1
00115 elif status.triangle and not latest.triangle:
00116
00117 res = self.get_stack_marker_pose_srv(self.pre_pose, [])
00118 elif status.start and not latest.start:
00119 self.toggle_footstep_marker_mode_srv()
00120
00121
00122 if self.current_goal_pose == None or not isSamePose(self.current_goal_pose.pose, self.pre_pose.pose):
00123 if self.pose_updated == False:
00124 marker_pose = self.getCurrentMarkerPose("movable_footstep_marker")
00125 if marker_pose != None and not isSamePose(self.pre_pose.pose, marker_pose.pose):
00126 self.pre_pose = marker_pose
00127 self.pose_updated = True
00128 if (now - self.prev_time).to_sec() > 1 / 30.0:
00129 self.pose_pub.publish(self.pre_pose)
00130 self.prev_time = now
00131 self.current_goal_pose = copy.deepcopy(self.pre_pose)
00132 else:
00133 self.pose_updated = False
00134
00135 def getCurrentMarkerPose(self, marker_name):
00136 try:
00137 marker_pose = self.get_footstep_marker_pose_srv(marker_name).pose_stamped
00138 if self.use_tf:
00139 marker_pose = self.tf_listener.transformPose(self.frame_id, marker_pose)
00140 return marker_pose
00141 except rospy.ServiceException, e:
00142 rospy.logwarn("Failed to get initial marker pose: %s", e)
00143 return None
00144 except tf.LookupException, e:
00145 rospy.logwarn("Failed to lookup tf: %s", e)
00146 return None