$search
00001 #!/usr/bin/env python 00002 00003 import roslib; roslib.load_manifest('checkerboard_detector2') 00004 import rospy 00005 import sys 00006 from visualization_msgs.msg import Marker, MarkerArray 00007 from geometry_msgs.msg import Vector3, Point, Pose, PoseArray 00008 from std_msgs.msg import ColorRGBA 00009 from sensor_msgs.msg import ChannelFloat32 00010 import logging 00011 import getopt 00012 import colorsys 00013 import numpy 00014 from transform_datatypes import * 00015 00016 def usage(progname): 00017 print __doc__ % vars() 00018 00019 class trackVisualizer: 00020 def __init__(self): 00021 self.pub = rospy.Publisher('visualization_marker', Marker) 00022 self.pub_array = rospy.Publisher('visualization_marker_array', MarkerArray) 00023 rospy.Subscriber("/camera/pose_array", PoseArray, self.callback) 00024 self.show_names = rospy.get_param('~show_names', True) 00025 00026 def callback(self, pose_array): 00027 #rospy.loginfo("received pose array of length %d" % len(pose_array.poses)) 00028 marker_array = MarkerArray() 00029 00030 self.render_axis(pose_array, marker_array) 00031 00032 #rospy.loginfo("publishing MarkerArray, containing %d markers", 00033 # len(marker_array.markers)) 00034 self.pub_array.publish(marker_array) 00035 00036 def render_axis(self, pose_array, marker_array): 00037 all_detected = True 00038 for p in pose_array.poses: 00039 r = [p.orientation.x,p.orientation.y,p.orientation.z,p.orientation.w] 00040 if( numpy.dot(r,r) == 0 ): 00041 all_detected = False 00042 00043 for i in range(len(pose_array.poses)): 00044 for axis in range(3): 00045 marker = Marker() 00046 marker.header.stamp = pose_array.header.stamp 00047 marker.header.frame_id = pose_array.header.frame_id 00048 marker.ns = "pose_axis_%d" % (i) 00049 marker.scale = Vector3(0.003, 0.003, 0.003) 00050 marker.id = (i*3 + axis)*3 00051 marker.action = Marker.ADD 00052 if all_detected: 00053 marker.color = self.generate_color_axis( axis / 3.0 ) 00054 else: 00055 marker.color = self.generate_color_axis( 0.00 ) 00056 marker.type = Marker.LINE_STRIP 00057 marker.pose = pose_array.poses[i] 00058 if axis == 0: 00059 marker.points.append(Point(0, 0, 0)) 00060 marker.points.append(Point(0.05, 0, 0)) 00061 elif axis == 1: 00062 marker.points.append(Point(0, 0, 0)) 00063 marker.points.append(Point(0, 0.05, 0)) 00064 elif axis == 2: 00065 marker.points.append(Point(0, 0, 0)) 00066 marker.points.append(Point(0, 0, 0.05)) 00067 marker_array.markers.append(marker) 00068 00069 if self.show_names: 00070 for i in range(len(pose_array.poses)): 00071 marker = Marker() 00072 marker.header.stamp = pose_array.header.stamp 00073 marker.header.frame_id = pose_array.header.frame_id 00074 marker.ns = "pose_name_%d" % (i) 00075 marker.scale = Vector3(0.05, 0.05, 0.05) 00076 marker.id = i 00077 marker.action = Marker.ADD 00078 if all_detected: 00079 marker.color = ColorRGBA(1.0,1.0,1.0, 1.0) 00080 else: 00081 marker.color = ColorRGBA(1.0,0.0,0.0, 1.0) 00082 marker.type = Marker.TEXT_VIEW_FACING 00083 marker.pose = mat44_to_pose((numpy.dot(pose_to_mat44(pose_array.poses[i]), 00084 tf.transformations.translation_matrix([0.0,0.0,0])))) 00085 marker.text = "x%d"%(i+1) 00086 marker_array.markers.append(marker) 00087 00088 00089 00090 def generate_color_axis(self, h=0,s=1,v=1): 00091 rgb = colorsys.hsv_to_rgb(h, s, v) 00092 return ColorRGBA(rgb[0], rgb[1], rgb[2], 1.0) 00093 00094 00095 def main(): 00096 try: 00097 rospy.init_node('pose_array_visualizer') 00098 trackVisualizer() 00099 rospy.spin() 00100 except rospy.ROSInterruptException: pass 00101 00102 if __name__ == '__main__': 00103 main() 00104