00001
00002 import rcommander.tool_utils as tu
00003
00004 from PyQt4.QtGui import *
00005 from PyQt4.QtCore import *
00006 import rospy
00007 import tf_utils as tfu
00008 import tf.transformations as tr
00009 import move_base_msgs.msg as mm
00010 import math
00011
00012
00013
00014
00015
00016 class NavigateTool(tu.ToolBase):
00017
00018 def __init__(self, rcommander):
00019 tu.ToolBase.__init__(self, rcommander, 'navigate', 'Navigate', NavigateState)
00020 self.tf_listener = rcommander.tf_listener
00021 self.default_frame = 'map'
00022 self.robot_frame_name = 'base_link'
00023
00024 def fill_property_box(self, pbox):
00025 formlayout = pbox.layout()
00026 self.xline = QLineEdit(pbox)
00027 self.yline = QLineEdit(pbox)
00028 self.tline = QLineEdit(pbox)
00029 self.frameline = QLineEdit(pbox)
00030 self.frameline.setText(self.default_frame)
00031 self.pose_button = QPushButton(pbox)
00032 self.pose_button.setText('Current Pose')
00033 self.pose_tool = QPushButton(pbox)
00034 self.pose_tool.setText('Specify Pose')
00035 self.reset()
00036
00037 formlayout.addRow("&x", self.xline)
00038 formlayout.addRow("&y", self.yline)
00039 formlayout.addRow("&theta", self.tline)
00040 formlayout.addRow("&frame", self.frameline)
00041 formlayout.addRow(self.pose_button)
00042 self.rcommander.connect(self.pose_button, SIGNAL('clicked()'), self.get_current_pose)
00043 formlayout.addRow(self.pose_tool)
00044 self.pose_tool.setEnabled(False)
00045
00046 pbox.update()
00047
00048
00049 def get_current_pose(self):
00050 frame = str(self.frameline.text())
00051 self.tf_listener.waitForTransform(frame, self.robot_frame_name, rospy.Time(), rospy.Duration(2.))
00052 p_base = tfu.transform(frame, self.robot_frame_name, self.tf_listener) \
00053 * tfu.tf_as_matrix(([0., 0., 0., 1.], tr.quaternion_from_euler(0,0,0)))
00054 t, r = tfu.matrix_as_tf(p_base)
00055 x = t[0]
00056 y = t[1]
00057 theta = tr.euler_from_quaternion(r)[2]
00058 print x,y,theta
00059
00060 self.xline.setText(str(x))
00061 self.yline.setText(str(y))
00062 self.tline.setText(str(math.degrees(theta)))
00063
00064 def new_node(self, name=None):
00065 xy = [float(self.xline.text()), float(self.yline.text())]
00066 theta = math.radians(float(self.tline.text()))
00067 frame = str(self.frameline.text())
00068 if name == None:
00069 nname = self.name + str(self.counter)
00070 else:
00071 nname = name
00072 state = NavigateState(nname, xy, theta, frame)
00073 return state
00074
00075 def set_node_properties(self, node):
00076 xy = node.xy
00077 self.xline.setText(str(xy[0]))
00078 self.yline.setText(str(xy[1]))
00079 self.tline.setText(str(math.degrees(node.theta)))
00080 self.frameline.setText(node.frame)
00081
00082
00083 def reset(self):
00084 self.xline.setText('0.')
00085 self.yline.setText('0.')
00086 self.tline.setText('0.')
00087 self.frameline.setText(self.default_frame)
00088
00089
00090
00091
00092
00093 class NavigateState(tu.SimpleStateBase):
00094
00095 def __init__(self, name, xy, theta, frame):
00096 tu.SimpleStateBase.__init__(self, name, \
00097 'move_base', mm.MoveBaseAction,
00098 goal_cb_str = 'ros_goal')
00099
00100 self.xy = xy
00101 self.theta = theta
00102 self.frame = frame
00103
00104 def ros_goal(self, userdata, default_goal):
00105 g = mm.MoveBaseGoal()
00106 p = g.target_pose
00107
00108 p.header.frame_id = 'map'
00109 p.header.stamp = rospy.get_rostime()
00110 p.pose.position.x = self.xy[0]
00111 p.pose.position.y = self.xy[1]
00112 p.pose.position.z = 0
00113
00114 p.pose.orientation.x = self.r[0]
00115 p.pose.orientation.y = self.r[1]
00116 p.pose.orientation.z = self.r[2]
00117 p.pose.orientation.w = self.r[3]
00118 return g
00119
00120 def _get_theta(self):
00121 return tr.euler_from_quaternion(self.r)[2]
00122
00123 def _set_theta(self, theta):
00124 self.r = tr.quaternion_from_euler(0, 0, theta)
00125
00126
00127
00128
00129
00130
00131
00132
00133 theta = property(_get_theta, _set_theta)
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151
00152