camera_control.py
Go to the documentation of this file.
00001 #!/usr/bin/python2
00002 
00003 # Copyright (c) 2013-2015, Rethink Robotics
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 # 1. Redistributions of source code must retain the above copyright notice,
00010 #    this list of conditions and the following disclaimer.
00011 # 2. Redistributions in binary form must reproduce the above copyright
00012 #    notice, this list of conditions and the following disclaimer in the
00013 #    documentation and/or other materials provided with the distribution.
00014 # 3. Neither the name of the Rethink Robotics nor the names of its
00015 #    contributors may be used to endorse or promote products derived from
00016 #    this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028 # POSSIBILITY OF SUCH DAMAGE.
00029 
00030 import argparse
00031 import socket
00032 import sys
00033 
00034 import rospy
00035 import rosgraph
00036 
00037 import std_srvs.srv
00038 
00039 from baxter_core_msgs.srv import (
00040     ListCameras,
00041 )
00042 from baxter_interface.camera import CameraController
00043 
00044 
00045 def list_cameras(*_args, **_kwds):
00046     ls = rospy.ServiceProxy('cameras/list', ListCameras)
00047     rospy.wait_for_service('cameras/list', timeout=10)
00048     resp = ls()
00049     if len(resp.cameras):
00050         # Find open (publishing) cameras
00051         master = rosgraph.Master('/rostopic')
00052         resp.cameras
00053         cam_topics = dict([(cam, "/cameras/%s/image" % cam)
00054                                for cam in resp.cameras])
00055         open_cams = dict([(cam, False) for cam in resp.cameras])
00056         try:
00057             topics = master.getPublishedTopics('')
00058             for topic in topics:
00059                 for cam in resp.cameras:
00060                     if topic[0] == cam_topics[cam]:
00061                         open_cams[cam] = True
00062         except socket.error:
00063             raise ROSTopicIOException("Cannot communicate with master.")
00064         for cam in resp.cameras:
00065             print("%s%s" % (cam, ("  -  (open)" if open_cams[cam] else "")))
00066     else:
00067         print ('No cameras found')
00068 
00069 
00070 def reset_cameras(*_args, **_kwds):
00071     reset_srv = rospy.ServiceProxy('cameras/reset', std_srvs.srv.Empty)
00072     rospy.wait_for_service('cameras/reset', timeout=10)
00073     reset_srv()
00074 
00075 
00076 def enum_cameras(*_args, **_kwds):
00077     try:
00078         reset_cameras()
00079     except:
00080         srv_ns = rospy.resolve_name('cameras/reset')
00081         rospy.logerr("Failed to call reset devices service at %s", srv_ns)
00082         raise
00083     else:
00084         list_cameras()
00085 
00086 
00087 def open_camera(camera, res, *_args, **_kwds):
00088     cam = CameraController(camera)
00089     cam.resolution = res
00090     cam.open()
00091 
00092 
00093 def close_camera(camera, *_args, **_kwds):
00094     cam = CameraController(camera)
00095     cam.close()
00096 
00097 
00098 def main():
00099     str_res = ["%rx%r" % (r[0], r[1]) for r in CameraController.MODES]
00100     fmt_res = ("Valid resolutions:\n[" +
00101               ("%s, " * (len(CameraController.MODES) - 1)) + "%s]")
00102     parser = argparse.ArgumentParser(
00103         formatter_class=argparse.RawDescriptionHelpFormatter,
00104         epilog=(fmt_res % tuple(str_res))
00105     )
00106     action_grp = parser.add_mutually_exclusive_group(required=True)
00107     action_grp.add_argument(
00108         '-o', '--open', metavar='CAMERA', help='Open specified camera'
00109     )
00110     parser.add_argument(
00111         '-r', '--resolution', metavar='[X]x[Y]', default='1280x800',
00112         help='Set camera resolution (default: 1280x800)'
00113     )
00114     action_grp.add_argument(
00115         '-c', '--close', metavar='CAMERA', help='Close specified camera'
00116     )
00117     action_grp.add_argument(
00118         '-l', '--list', action='store_true', help='List available cameras'
00119     )
00120     action_grp.add_argument(
00121         '-e', '--enumerate', action='store_true',
00122         help='Clear and re-enumerate connected devices'
00123     )
00124     args = parser.parse_args(rospy.myargv()[1:])
00125 
00126     action = None
00127     camera = None
00128     res = (1280, 800)
00129 
00130     if args.list:
00131         action = list_cameras
00132     elif args.open:
00133         action = open_camera
00134         camera = args.open
00135         lres = args.resolution.split('x')
00136         if len(lres) != 2:
00137             print fmt_res % tuple(str_res)
00138             parser.error("Invalid resolution format: %s. Use (X)x(Y).")
00139         res = (int(lres[0]), int(lres[1]))
00140         if not any((res[0] == r[0] and res[1] == r[1])
00141                    for r in CameraController.MODES):
00142             print fmt_res % tuple(str_res)
00143             parser.error("Invalid resolution provided.")
00144     elif args.close:
00145         action = close_camera
00146         camera = args.close
00147     elif args.enumerate:
00148         action = enum_cameras
00149     else:
00150         # Should not reach here with required action_grp
00151         parser.print_usage()
00152         parser.error("No action defined.")
00153 
00154     rospy.init_node('rsdk_camera_control')
00155     action(camera, res)
00156     return 0
00157 
00158 if __name__ == '__main__':
00159     sys.exit(main())


baxter_tools
Author(s): Rethink Robotics Inc.
autogenerated on Wed Aug 26 2015 10:50:53