Go to the documentation of this file.00001
00002 from __future__ import division
00003
00004 import roslib; roslib.load_manifest('projected_interface_builder')
00005 from projected_interface_builder.projected_interface import ProjectedInterface
00006 from projected_interface_builder.data_structures import PolygonInfo
00007 from projected_interface_builder.convert_utils import QtPolyToROS, QtRectToPoly
00008 import rospy
00009
00010 import sys
00011
00012 class ConfigTestInterface(ProjectedInterface):
00013 def __init__(self, polygon_file):
00014 super(ConfigTestInterface, self).__init__(polygon_file)
00015
00016
00017 while not rospy.has_param('/screen/height'):
00018 rospy.sleep(0.1)
00019
00020 self.width = float(rospy.get_param('/screen/width'))
00021 self.height = float(rospy.get_param('/screen/height'))
00022
00023
00024 def updatePosition(self):
00025 square = self.polygons['square']
00026 ps = QtPolyToROS(square.polygon, square.id, interf.x, interf.y, interf.z, interf.res, '/bottom_left')
00027
00028
00029 left = min(
00030 ps.polygon.points[0].x,
00031 ps.polygon.points[1].x,
00032 ps.polygon.points[2].x,
00033 ps.polygon.points[3].x,
00034 )
00035
00036 right = max(
00037 ps.polygon.points[0].x,
00038 ps.polygon.points[1].x,
00039 ps.polygon.points[2].x,
00040 ps.polygon.points[3].x,
00041 )
00042
00043 top = max(
00044 ps.polygon.points[0].y,
00045 ps.polygon.points[1].y,
00046 ps.polygon.points[2].y,
00047 ps.polygon.points[3].y,
00048 )
00049
00050 bottom = min(
00051 ps.polygon.points[0].y,
00052 ps.polygon.points[1].y,
00053 ps.polygon.points[2].y,
00054 ps.polygon.points[3].y,
00055 )
00056
00057 poly_width = abs(right-left)
00058
00059 square.text_rect = square.polygon.boundingRect()
00060 square.text_rect.setTop(square.text_rect.top() + 20)
00061 self.x = (self.width/2)
00062 self.y = self.height/2
00063 print self.x, self.y
00064
00065 self.publish_polygons()
00066
00067 if __name__ == '__main__':
00068 rospy.init_node('config_test_interface')
00069 interf = ConfigTestInterface(sys.argv[1])
00070 interf.start()
00071 interf.updatePosition()
00072 rospy.spin()
00073