joy_footstep_marker.py
Go to the documentation of this file.
1 import rospy
2 
3 import imp
4 try:
5  imp.find_module("actionlib")
6 except:
7  import roslib; roslib.load_manifest('jsk_teleop_joy')
8 
9 import actionlib
10 from jsk_rviz_plugins.msg import OverlayMenu
11 from joy_pose_6d import JoyPose6D
12 from jsk_interactive_marker.srv import GetTransformableMarkerPose
13 from jsk_interactive_marker.srv import SetPose
14 from geometry_msgs.msg import PoseStamped
15 from std_srvs.srv import Empty
16 import copy
17 import time
18 import tf
19 
20 def isSamePose(pose1, pose2):
21  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"]])
22 
23 class JoyFootstepMarker(JoyPose6D):
24  '''
25 Usage:
26 Refer JoyPose6D
27 circle: execute footstep
28 cross: reset marker
29 triangle: stack footstep (only used in stack mode)
30 start: toggle footstep marker mode (single -> continuous -> stack)
31 
32 Args:
33 use_tf [Boolean, default: True]: update marker pose using tf
34 publish_pose : forced False
35 frame_id [String, default: map]: frame_id of publishing pose, this is overwritten by parameter, ~frame_id
36 pose [String, default: pose]: topic name for publishing pose
37 set_pose [String, default: set_pose]: topic name for setting pose by topic
38  '''
39  def __init__(self, name, args):
40  args['publish_pose'] = False # supress publishing pose of joy_pose_6d
41  JoyPose6D.__init__(self, name, args)
42  self.pose_pub = rospy.Publisher(self.getArg('pose', 'pose'), PoseStamped)
43  self.current_goal_pose = None
44  self.use_tf = self.getArg('use_tf', True)
45  self.pose_updated = False
46 
47  # make publisher
48  self.pub = rospy.Publisher("joy_footstep_menu", OverlayMenu)
49  self.menu = None
50 
51  # make service proxy
52  rospy.wait_for_service('/footstep_marker/reset_marker')
53  self.reset_marker_srv = rospy.ServiceProxy('/footstep_marker/reset_marker', Empty)
54  rospy.wait_for_service('/footstep_marker/toggle_footstep_marker_mode')
55  self.toggle_footstep_marker_mode_srv = rospy.ServiceProxy('/footstep_marker/toggle_footstep_marker_mode', Empty)
56  rospy.wait_for_service('/footstep_marker/execute_footstep')
57  self.execute_footstep_srv = rospy.ServiceProxy('/footstep_marker/execute_footstep', Empty)
58  rospy.wait_for_service('/footstep_marker/get_footstep_marker_pose')
59  self.get_footstep_marker_pose_srv = rospy.ServiceProxy('/footstep_marker/get_footstep_marker_pose', GetTransformableMarkerPose)
60  rospy.wait_for_service('/footstep_marker/stack_marker_pose')
61  self.get_stack_marker_pose_srv = rospy.ServiceProxy('/footstep_marker/stack_marker_pose', SetPose)
62 
63  # initialize maker pose
64  marker_pose = self.getCurrentMarkerPose("movable_footstep_marker")
65  if marker_pose != None:
66  self.pre_pose = marker_pose
67 
68  def joyCB(self, status, history):
69  now = rospy.Time.from_sec(time.time())
70  latest = history.latest()
71  if not latest:
72  return
73 
74  # menu mode
75  if self.menu != None:
76  if status.up and not latest.up:
77  self.menu.current_index = (self.menu.current_index - 1) % len(self.menu.menus)
78  self.pub.publish(self.menu)
79  elif status.down and not latest.down:
80  self.menu.current_index = (self.menu.current_index + 1) % len(self.menu.menus)
81  self.pub.publish(self.menu)
82  elif status.circle and not latest.circle:
83  self.menu.action = OverlayMenu.ACTION_CLOSE
84  if self.menu.current_index == self.menu.menus.index("Yes"):
85  try:
87  except rospy.ServiceException as e:
88  rospy.logwarn("Execute Footsteps failed: %s", e)
89  self.pub.publish(self.menu)
90  self.menu = None
91  elif status.cross and not latest.cross:
92  self.menu.action = OverlayMenu.ACTION_CLOSE
93  self.pub.publish(self.menu)
94  self.menu = None
95  else:
96  self.pub.publish(self.menu)
97  return
98 
99  # control mode
100  JoyPose6D.joyCB(self, status, history)
101  if status.circle and not latest.circle: # go into execute footsteps menu
102  self.menu = OverlayMenu()
103  self.menu.title = "Execute Footsteps?"
104  self.menu.menus = ["Yes", "No"]
105  self.menu.current_index = 1
106  self.pub.publish(self.menu)
107  elif status.cross and not latest.cross: # reset marker
108  self.reset_marker_srv()
109  marker_pose = self.getCurrentMarkerPose("initial_footstep_marker")
110  if marker_pose != None:
111  self.pre_pose = marker_pose
112  else:
113  self.pre_pose = PoseStamped()
114  self.pre_pose.pose.orientation.w = 1
115  elif status.triangle and not latest.triangle:
116  #req = SetPoseRequest(self.pre_pose)
117  res = self.get_stack_marker_pose_srv(self.pre_pose, [])
118  elif status.start and not latest.start: # toggle footstep_marker mode
120 
121  # synchronize marker_pose, which may be modified by interactive marker
122  if self.current_goal_pose == None or not isSamePose(self.current_goal_pose.pose, self.pre_pose.pose):
123  if self.pose_updated == False:
124  marker_pose = self.getCurrentMarkerPose("movable_footstep_marker") # synchronize marker_pose only at first of pose update
125  if marker_pose != None and not isSamePose(self.pre_pose.pose, marker_pose.pose):
126  self.pre_pose = marker_pose
127  self.pose_updated = True
128  if (now - self.prev_time).to_sec() > 1 / 30.0:
129  self.pose_pub.publish(self.pre_pose)
130  self.prev_time = now
131  self.current_goal_pose = copy.deepcopy(self.pre_pose)
132  else:
133  self.pose_updated = False
134 
135  def getCurrentMarkerPose(self, marker_name):
136  try:
137  marker_pose = self.get_footstep_marker_pose_srv(marker_name).pose_stamped
138  if self.use_tf:
139  marker_pose = self.tf_listener.transformPose(self.frame_id, marker_pose)
140  return marker_pose
141  except rospy.ServiceException as e:
142  rospy.logwarn("Failed to get initial marker pose: %s", e)
143  return None
144  except tf.LookupException as e:
145  rospy.logwarn("Failed to lookup tf: %s", e)
146  return None


jsk_teleop_joy
Author(s): Ryohei Ueda
autogenerated on Fri May 14 2021 02:52:11