$search
00001 #! /usr/bin/env python 00002 00003 import roslib 00004 roslib.load_manifest('nao_driver') 00005 import rospy 00006 from sensor_msgs.msg import Image, CameraInfo 00007 from nao_driver import NaoNode 00008 from sensor_msgs.srv import SetCameraInfo 00009 00010 00011 from naoqi import ALProxy 00012 from vision_definitions import * 00013 00014 00015 class NaoCam (NaoNode): 00016 def __init__(self): 00017 NaoNode.__init__(self) 00018 rospy.init_node('nao_camera') 00019 self.camProxy = self.getProxy("ALVideoDevice") 00020 if self.camProxy is None: 00021 exit(1) 00022 00023 # ROS pub/sub 00024 self.pub_img_ = rospy.Publisher('image_raw', Image) 00025 self.pub_info_ = rospy.Publisher('camera_info', CameraInfo) 00026 self.set_camera_info_service_ = rospy.Service('set_camera_info', SetCameraInfo, self.set_camera_info) 00027 # Messages 00028 self.info_ = CameraInfo() 00029 self.set_default_params_qvga(self.info_) #default params should be overwritten by service call 00030 # parameters 00031 self.camera_switch = rospy.get_param('~camera_switch', 0) 00032 if self.camera_switch == 0: 00033 self.frame_id = "/CameraTop_frame" 00034 elif self.camera_switch == 1: 00035 self.frame_id = "/CameraBottom_frame" 00036 else: 00037 rospy.logerr('Invalid camera_switch. Must be 0 or 1') 00038 exit(1) 00039 print "Using namespace ", rospy.get_namespace() 00040 print "using camera: ", self.camera_switch 00041 #TODO: parameters 00042 self.resolution = kQVGA 00043 self.colorSpace = kBGRColorSpace 00044 self.fps = 30 00045 # init 00046 self.nameId = '' 00047 self.subscribe() 00048 00049 def subscribe(self): 00050 # unsubscribe for all zombie subscribers 00051 self.camProxy.unsubscribeAllInstances("rospy_gvm") 00052 00053 # subscribe 00054 self.nameId = self.camProxy.subscribe("rospy_gvm", self.resolution, self.colorSpace, self.fps) 00055 #print "subscriber name is ", self.nameId 00056 00057 # set params 00058 rospy.sleep(1) 00059 self.camProxy.setParam(kCameraSelectID, self.camera_switch) 00060 self.camProxy.setResolution(self.nameId, self.resolution) 00061 00062 def set_camera_info(self, cameraInfoMsg): 00063 print "Received new camera info" 00064 self.info_ = cameraInfoMsg.camera_info 00065 00066 00067 00068 def set_default_params_qvga(self, cam_info): 00069 cam_info.P[0] = 382.92 00070 cam_info.P[1] = 0.0 00071 cam_info.P[2] = 160.0 00072 cam_info.P[3] = 0 00073 cam_info.P[4] = 0.0 00074 cam_info.P[5] = 373.31 00075 cam_info.P[6] = 120.0 00076 cam_info.P[7] = 0.0 00077 cam_info.P[8] = 0.0 00078 cam_info.P[9] = 0.0 00079 cam_info.P[10] = 1.0 00080 cam_info.P[11] = 0.0 00081 00082 def main_loop(self): 00083 img = Image() 00084 while not rospy.is_shutdown(): 00085 #print "getting image..", 00086 image = self.camProxy.getImageRemote(self.nameId) 00087 #print "ok" 00088 # TODO: better time 00089 img.header.stamp = rospy.Time.now() 00090 img.header.frame_id = self.frame_id 00091 img.height = image[1] 00092 img.width = image[0] 00093 nbLayers = image[2] 00094 #colorspace = image[3] 00095 if image[3] == kYUVColorSpace: 00096 encoding = "mono8" 00097 elif image[3] == kRGBColorSpace: 00098 encoding = "rgb8" 00099 elif image[3] == kBGRColorSpace: 00100 encoding = "bgr8" 00101 else: 00102 rospy.logerror("Received unknown encoding: {0}".format(image[3])) 00103 00104 img.encoding = encoding 00105 img.step = img.width * nbLayers 00106 img.data = image[6] 00107 self.info_.width = img.width 00108 self.info_.height = img.height 00109 self.info_.header = img.header 00110 self.pub_img_.publish(img) 00111 self.pub_info_.publish(self.info_) 00112 rospy.sleep(0.0001)# TODO: is this necessary? 00113 00114 00115 self.camProxy.unsubscribe(self.nameId) 00116 00117 if __name__ == "__main__": 00118 try: 00119 naocam = NaoCam() 00120 naocam.main_loop() 00121 except RuntimeError, e: 00122 rospy.logerr('Something went wrong: %s' % (e) ) 00123 rospy.loginfo('Camera stopped')