camera.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 #
00004 # ROS node to provide access to the camera by wrapping NaoQI access (may not
00005 # be the most efficient way...)
00006 #
00007 # Copyright 2012 Daniel Maier, University of Freiburg
00008 # Copyright 2014 Aldebaran Robotics
00009 # http://www.ros.org/wiki/nao
00010 #
00011 # Redistribution and use in source and binary forms, with or without
00012 # modification, are permitted provided that the following conditions are met:
00013 #
00014 #    # Redistributions of source code must retain the above copyright
00015 #       notice, this list of conditions and the following disclaimer.
00016 #    # Redistributions in binary form must reproduce the above copyright
00017 #       notice, this list of conditions and the following disclaimer in the
00018 #       documentation and/or other materials provided with the distribution.
00019 #    # Neither the name of the University of Freiburg nor the names of its
00020 #       contributors may be used to endorse or promote products derived from
00021 #       this software without specific prior written permission.
00022 #
00023 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00024 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00025 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00026 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00027 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00028 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00029 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00030 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00031 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00032 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 #
00035 
00036 from collections import defaultdict
00037 from distutils.version import LooseVersion
00038 import rospy
00039 from sensor_msgs.msg import Image, CameraInfo
00040 from nao_driver.nao_driver_naoqi import NaoNode
00041 import camera_info_manager
00042 
00043 from dynamic_reconfigure.server import Server
00044 from nao_sensors.cfg import NaoCameraConfig
00045 
00046 # import resolutions
00047 from nao_sensors.vision_definitions import k960p, k4VGA, kVGA, kQVGA, kQQVGA
00048 # import color spaces
00049 from nao_sensors.vision_definitions import kYUV422ColorSpace, kYUVColorSpace, \
00050                     kRGBColorSpace, kBGRColorSpace, kDepthColorSpace
00051 # import extra parameters
00052 from nao_sensors.vision_definitions import kCameraSelectID, kCameraAutoExpositionID, kCameraAecAlgorithmID, \
00053                   kCameraContrastID, kCameraSaturationID, kCameraHueID, kCameraSharpnessID, kCameraAutoWhiteBalanceID, \
00054                   kCameraExposureID, kCameraGainID, kCameraBrightnessID, kCameraWhiteBalanceID
00055 
00056 # those should appear in vision_definitions.py at some point
00057 kTopCamera = 0
00058 kBottomCamera = 1
00059 kDepthCamera = 2
00060 
00061 class NaoCam (NaoNode):
00062     def __init__(self):
00063         NaoNode.__init__(self, 'nao_camera')
00064 
00065         self.camProxy = self.get_proxy("ALVideoDevice")
00066         if self.camProxy is None:
00067             exit(1)
00068         self.nameId = None
00069         self.camera_infos = {}
00070         def returnNone():
00071             return None
00072         self.config = defaultdict(returnNone)
00073 
00074         # ROS publishers
00075         self.pub_img_ = rospy.Publisher('~image_raw', Image, queue_size=5)
00076         self.pub_info_ = rospy.Publisher('~camera_info', CameraInfo, queue_size=5)
00077 
00078         # initialize the parameter server
00079         self.srv = Server(NaoCameraConfig, self.reconfigure)
00080 
00081         # initially load configurations
00082         self.reconfigure(self.config, 0)
00083 
00084     def reconfigure( self, new_config, level ):
00085         """
00086         Reconfigure the camera
00087         """
00088         rospy.loginfo('reconfigure changed')
00089         if self.pub_img_.get_num_connections() == 0:
00090             rospy.loginfo('Changes recorded but not applied as nobody is subscribed to the ROS topics.')
00091             self.config.update(new_config)
00092             return self.config
00093 
00094         # check if we are even subscribed to a camera
00095         is_camera_new = self.nameId is None
00096 
00097         if is_camera_new:
00098             rospy.loginfo('subscribed to camera proxy, since this is the first camera')
00099             if self.get_version() < LooseVersion('2.0'):
00100                 self.nameId = self.camProxy.subscribe("rospy_gvm", new_config['source'],
00101                                                       new_config['resolution'], new_config['color_space'],
00102                                                       new_config['frame_rate'])
00103             else:
00104                 self.nameId = self.camProxy.subscribeCamera("rospy_gvm", new_config['source'],
00105                                                             new_config['resolution'], new_config['color_space'],
00106                                                             new_config['frame_rate'])
00107 
00108         if self.config['source'] != new_config['source'] or is_camera_new:
00109             rospy.loginfo('updating camera source information')
00110 
00111             if new_config['source'] == kTopCamera:
00112                 self.frame_id = "/CameraTop_frame"
00113             elif new_config['source'] == kBottomCamera:
00114                 self.frame_id = "/CameraBottom_frame"
00115             elif new_config['source'] == kDepthCamera:
00116                 self.frame_id = new_config['camera3d_frame']
00117             else:
00118                 rospy.logerr('Invalid source. Must be 0, 1 or 2')
00119                 exit(1)
00120 
00121         # check if the camera changed
00122         if self.config['camera_info_url'] != new_config['camera_info_url'] and \
00123                         new_config['camera_info_url'] and new_config['camera_info_url'] not in self.camera_infos:
00124             if 'cim' not in self.__dict__:
00125                 self.cim = camera_info_manager.CameraInfoManager(cname='nao_camera')
00126 
00127             if not self.cim.setURL( new_config['camera_info_url'] ):
00128                 rospy.logerr('malformed URL for calibration file')
00129             else:
00130                 try:
00131                     self.cim.loadCameraInfo()
00132                 except IOExcept:
00133                     rospy.logerr('Could not read from existing calibration file')
00134 
00135             if self.cim.isCalibrated():
00136                 rospy.loginfo('Successfully loaded camera info')
00137                 self.camera_infos[new_config['camera_info_url']] = self.cim.getCameraInfo()
00138             else:
00139                 rospy.logerr('There was a problem loading the calibration file. Check the URL!')
00140 
00141         # set params
00142         key_naoqi_keys = [('auto_exposition', kCameraAutoExpositionID),
00143                           ('auto_exposure_algo', kCameraAecAlgorithmID),
00144                           ('contrast', kCameraContrastID), ('saturation', kCameraSaturationID),
00145                           ('hue', kCameraHueID), ('sharpness', kCameraSharpnessID),
00146                           ('auto_white_balance', kCameraAutoWhiteBalanceID)]
00147         if self.get_version() < LooseVersion('2.0'):
00148             key_method.append(('source', 'setActiveCamera'))
00149 
00150         for key, naoqi_key in key_naoqi_keys:
00151             if self.config[key] != new_config[key] or is_camera_new:
00152                 if self.get_version() < LooseVersion('2.0'):
00153                     self.camProxy.setParam(naoqi_key, new_config[key])
00154                 else:
00155                     self.camProxy.setCamerasParameter(self.nameId, naoqi_key, new_config[key])
00156 
00157         for key, naoqi_key, auto_exp_val in [('exposure', kCameraExposureID, 0),
00158                                              ('gain', kCameraGainID, 0), ('brightness', kCameraBrightnessID, 1)]:
00159             if self.config[key] != new_config[key] or is_camera_new:
00160                 if self.get_version() < LooseVersion('2.0'):
00161                     self.camProxy.setParam(kCameraAutoExpositionID, auto_exp_val)
00162                     self.camProxy.setParam(naoqi_key, new_config[key])
00163                 else:
00164                     self.camProxy.setCamerasParameter(self.nameId, kCameraAutoExpositionID, auto_exp_val)
00165                     self.camProxy.setCamerasParameter(self.nameId, naoqi_key, new_config[key])
00166 
00167         if self.config['white_balance'] != new_config['white_balance'] or is_camera_new:
00168             if self.get_version() < LooseVersion('2.0'):
00169                 self.camProxy.setParam(kCameraAutoWhiteBalanceID, 0)
00170                 self.camProxy.setParam(kCameraWhiteBalanceID, new_config['white_balance'])
00171             else:
00172                 self.camProxy.setCamerasParameter(self.nameId, kCameraAutoWhiteBalanceID, 0)
00173                 self.camProxy.setCamerasParameter(self.nameId, kCameraWhiteBalanceID, new_config['white_balance'])
00174 
00175         key_methods =  [ ('resolution', 'setResolution'), ('color_space', 'setColorSpace'), ('frame_rate', 'setFrameRate')]
00176         if self.get_version() >= LooseVersion('2.0'):
00177             key_methods.append(('source', 'setActiveCamera'))
00178         for key, method in key_methods:
00179             if self.config[key] != new_config[key] or is_camera_new:
00180                 self.camProxy.__getattribute__(method)(self.nameId, new_config[key])
00181 
00182         self.config.update(new_config)
00183 
00184         return self.config
00185 
00186     def run(self):
00187         img = Image()
00188         r = rospy.Rate(self.config['frame_rate'])
00189         while self.is_looping():
00190             if self.pub_img_.get_num_connections() == 0:
00191                 if self.nameId:
00192                     rospy.loginfo('Unsubscribing from camera as nobody listens to the topics.')
00193                     self.camProxy.unsubscribe(self.nameId)
00194                     self.nameId = None
00195                 r.sleep()
00196                 continue
00197             if self.nameId is None:
00198                 self.reconfigure(self.config, 0)
00199                 r.sleep()
00200                 continue
00201             image = self.camProxy.getImageRemote(self.nameId)
00202             if image is None:
00203                 continue
00204             # Deal with the image
00205             if self.config['use_ros_time']:
00206                 img.header.stamp = rospy.Time.now()
00207             else:
00208                 img.header.stamp = rospy.Time(image[4] + image[5]*1e-6)
00209             img.header.frame_id = self.frame_id
00210             img.height = image[1]
00211             img.width = image[0]
00212             nbLayers = image[2]
00213             if image[3] == kYUVColorSpace:
00214                 encoding = "mono8"
00215             elif image[3] == kRGBColorSpace:
00216                 encoding = "rgb8"
00217             elif image[3] == kBGRColorSpace:
00218                 encoding = "bgr8"
00219             elif image[3] == kYUV422ColorSpace:
00220                 encoding = "yuv422" # this works only in ROS groovy and later
00221             elif image[3] == kDepthColorSpace:
00222                 encoding = "mono16"
00223             else:
00224                 rospy.logerr("Received unknown encoding: {0}".format(image[3]))
00225             img.encoding = encoding
00226             img.step = img.width * nbLayers
00227             img.data = image[6]
00228 
00229             self.pub_img_.publish(img)
00230 
00231             # deal with the camera info
00232             if self.config['source'] == kDepthCamera and image[3] == kDepthColorSpace:
00233                 infomsg = CameraInfo()
00234                 # yes, this is only for an XTion / Kinect but that's the only thing supported by NAO
00235                 ratio_x = float(640)/float(img.width)
00236                 ratio_y = float(480)/float(img.height)
00237                 infomsg.width = img.width
00238                 infomsg.height = img.height
00239                 # [ 525., 0., 3.1950000000000000e+02, 0., 525., 2.3950000000000000e+02, 0., 0., 1. ]
00240                 infomsg.K = [ 525, 0, 3.1950000000000000e+02,
00241                               0, 525, 2.3950000000000000e+02,
00242                               0, 0, 1 ]
00243                 infomsg.P = [ 525, 0, 3.1950000000000000e+02, 0,
00244                               0, 525, 2.3950000000000000e+02, 0,
00245                               0, 0, 1, 0 ]
00246                 for i in range(3):
00247                     infomsg.K[i] = infomsg.K[i] / ratio_x
00248                     infomsg.K[3+i] = infomsg.K[3+i] / ratio_y
00249                     infomsg.P[i] = infomsg.P[i] / ratio_x
00250                     infomsg.P[4+i] = infomsg.P[4+i] / ratio_y
00251 
00252                 infomsg.D = []
00253                 infomsg.binning_x = 0
00254                 infomsg.binning_y = 0
00255                 infomsg.distortion_model = ""
00256                 self.pub_info_.publish(infomsg)
00257 
00258             elif self.config['camera_info_url'] in self.camera_infos:
00259                 infomsg = self.camera_infos[self.config['camera_info_url']]
00260                 infomsg.header = img.header
00261                 self.pub_info_.publish(infomsg)
00262 
00263             r.sleep()
00264 
00265         if (self.nameId):
00266             rospy.loginfo("unsubscribing from camera ")
00267             self.camProxy.unsubscribe(self.nameId)
00268 
00269 if __name__ == "__main__":
00270     naocam = NaoCam()
00271     naocam.start()
00272     rospy.spin()


nao_sensors
Author(s): Séverin Lemaignan, Vincent Rabaud, Karsten Knese, Jack O'Quin, Ken Tossell, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy, Daniel Maier
autogenerated on Mon Oct 6 2014 02:40:25