5 imp.find_module(
"actionlib")
7 import roslib; roslib.load_manifest(
'jsk_teleop_joy')
10 from jsk_teleop_joy.joy_pose_6d
import JoyPose6D
11 from actionlib_msgs.msg
import GoalStatusArray
12 from jsk_footstep_msgs.msg
import PlanFootstepsAction, PlanFootstepsGoal, Footstep, FootstepArray, ExecFootstepsAction, ExecFootstepsGoal
13 from jsk_rviz_plugins.msg
import OverlayMenu, OverlayText
14 from std_msgs.msg
import UInt8, Empty
15 from std_srvs.srv
import Empty
as EmptySrv
19 from geometry_msgs.msg
import PoseStamped
21 from jsk_footstep_planner.srv
import ChangeSuccessor
27 CANCELED_MENUS = [
"Cancel",
29 "Use larger footsteps",
30 "Use middle footsteps",
31 "Use smaller footsteps"]
33 JoyPose6D.__init__(self, name, args)
34 self.
usage_pub = rospy.Publisher(
"/joy/usage", OverlayText)
35 self.supportFollowView(
True)
40 self.
frame_id = self.getArg(
'frame_id',
'/map')
43 self.
lfoot_offset = tf_ext.xyzxyzwToMatrix(rospy.get_param(
'~lfoot_offset'))
44 self.
rfoot_offset = tf_ext.xyzxyzwToMatrix(rospy.get_param(
'~rfoot_offset'))
48 self.
execute_pub = rospy.Publisher(self.getArg(
'execute',
'execute'), Empty)
49 self.
resume_pub = rospy.Publisher(self.getArg(
'resume',
'resume'), Empty)
51 self.
menu_pub = rospy.Publisher(
"/overlay_menu", OverlayMenu)
55 rospy.Time(0.0), rospy.Duration(100.0))
58 rospy.Time(0.0), rospy.Duration(100.0))
61 self.
status_sub = rospy.Subscriber(
"/footstep_controller/status", GoalStatusArray,
63 self.
snap_sub = rospy.Subscriber(self.getArg(
"snapped_pose",
"/footstep_marker/snapped_pose"),
76 except rospy.ServiceException
as e:
77 rospy.logerror(
"failed to call service: %s" % (e.message))
82 except rospy.ServiceException
as e:
83 rospy.logerror(
"failed to call service: %s" % (e.message))
90 if len(msg.status_list) == 0:
94 if self.
mode == self.
EXECUTING and msg.status_list[0].status == 0:
106 overlay_text = OverlayText()
107 overlay_text.text =
"""
115 triangle : Clear maps and look around ground
116 up/down : Move menu cursors
118 overlay_text.width = 500
119 overlay_text.height = 500
120 overlay_text.text_size = 12
121 overlay_text.left = 10
122 overlay_text.top = 10
123 overlay_text.font =
"Ubuntu Mono Regular"
124 overlay_text.bg_color.a = 0
125 overlay_text.fg_color.r = 25 / 255.0
126 overlay_text.fg_color.g = 1
127 overlay_text.fg_color.b = 1
128 overlay_text.fg_color.a = 1
133 lfoot_pose = tf_ext.transformToMatrix(self.
tf_listener.lookupTransform(
137 rfoot_pose = tf_ext.transformToMatrix(self.
tf_listener.lookupTransform(
142 lfoot_with_offset = numpy.dot(lfoot_pose, self.
lfoot_offset)
143 rfoot_with_offset = numpy.dot(rfoot_pose, self.
rfoot_offset)
144 (lfoot_pos, lfoot_q) = tf_ext.decomposeMatrix(lfoot_with_offset)
145 (rfoot_pos, rfoot_q) = tf_ext.decomposeMatrix(rfoot_with_offset)
147 mid_pos = (lfoot_pos + rfoot_pos) / 2.0
148 mid_quaternion = quaternion_slerp(lfoot_q, rfoot_q,
150 self.pre_pose.pose.position.x = mid_pos[0]
151 self.pre_pose.pose.position.y = mid_pos[1]
152 self.pre_pose.pose.position.z = mid_pos[2]
153 self.pre_pose.pose.orientation.x = mid_quaternion[0]
154 self.pre_pose.pose.orientation.y = mid_quaternion[1]
155 self.pre_pose.pose.orientation.z = mid_quaternion[2]
156 self.pre_pose.pose.orientation.w = mid_quaternion[3]
167 menu.title =
"Canceled"
169 menu.action = OverlayMenu.ACTION_CLOSE
173 change_successor = rospy.ServiceProxy(
'/change_successor', ChangeSuccessor)
174 change_successor(successor_type)
175 except rospy.ServiceException
as e:
176 rospy.logerror(
"failed to call service: %s" % (e.message))
179 if selected_title ==
"Cancel":
184 elif selected_title ==
"Ignore and proceed":
191 elif selected_title ==
"Use smaller footsteps":
197 elif (selected_title ==
"Use larger footsteps" or
198 selected_title ==
"Use middle footsteps"):
206 clear_maps = rospy.ServiceProxy(
'/env_server/clear_maps', std_srvs.srv.Empty)
208 look_around = rospy.ServiceProxy(
'/lookaround_ground', std_srvs.srv.Empty)
210 except Exception
as e:
211 rospy.logerr(
"error when lookaround ground: %s", e.message)
217 JoyPose6D.joyCB(self, status, history)
218 if history.new(status,
"circle"):
226 elif history.new(status,
"cross"):
228 elif history.new(status,
"triangle"):
232 if history.new(status,
"circle"):
236 if history.new(status,
"up"):
238 elif history.new(status,
"down"):
249 if history.new(status,
"cross"):