diff --git a/.gitignore b/.gitignore index d53a461..20ac71f 100644 --- a/.gitignore +++ b/.gitignore @@ -2,3 +2,5 @@ *.tar.gz *~ TAGS +axis_214_PTZ_standalone.urdf +doc/html diff --git a/CMakeLists.txt b/CMakeLists.txt index 78d8aa9..9c5f75a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,30 +1,59 @@ cmake_minimum_required(VERSION 2.8.3) project(axis_camera) -find_package(catkin REQUIRED - COMPONENTS +set(THIS_PACKAGE_MESSAGE_DEPS + sensor_msgs + std_msgs +) +# packages which are both build and run dependencies +set(THIS_PACKAGE_DEPS + camera_info_manager_py + diagnostic_aggregator + diagnostic_msgs + diagnostic_updater dynamic_reconfigure - geometry_msgs - message_generation + rospy + sensor_msgs std_msgs + tf + ${THIS_PACKAGE_MESSAGE_DEPS} ) + +find_package(catkin REQUIRED COMPONENTS message_generation xacro ${THIS_PACKAGE_DEPS}) catkin_python_setup() # ROS message generation -add_message_files(FILES Axis.msg) -generate_messages(DEPENDENCIES geometry_msgs std_msgs) -generate_dynamic_reconfigure_options(cfg/PTZ.cfg) +add_message_files(FILES + PTZ.msg + PointInRectangle.msg + Axis.msg # deprecated +) +add_service_files(FILES + TakeSnapshot.srv +) +generate_messages(DEPENDENCIES ${THIS_PACKAGE_MESSAGE_DEPS}) -catkin_package() +generate_dynamic_reconfigure_options( + cfg/Camera.cfg + cfg/VideoStream.cfg + cfg/PTZ.cfg # deprecated +) + +# Generate the standalone URDF version. +xacro_add_xacro_file(${CMAKE_CURRENT_SOURCE_DIR}/urdf/axis_214_PTZ_standalone.xacro + ${CMAKE_CURRENT_SOURCE_DIR}/urdf/axis_214_PTZ_standalone.urdf) +add_custom_target(axis_camera_media_files_urdf ALL DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/urdf/axis_214_PTZ_standalone.urdf) + +catkin_package(CATKIN_DEPENDS message_runtime ${THIS_PACKAGE_DEPS}) install(PROGRAMS nodes/axis.py nodes/axis_ptz.py - nodes/publish_axis_tf.py nodes/teleop.py nodes/teleop_speed_control.py + nodes/keyboard_teleop.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) -install(DIRECTORY launch tests +install(DIRECTORY launch tests meshes urdf DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) - +install(FILES diag.yaml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/README.rst b/README.rst index a877a84..3d96f51 100644 --- a/README.rst +++ b/README.rst @@ -1,26 +1,14 @@ -Overview -======== +Axis camera driver for ROS +========================== -This ROS_ package provides an `Axis network camera`_ driver, written -in Python. +This ROS_ package provides an `Axis network camera`_ driver, written in Python. It provides both a ROS API (via ROS topics and parameters) and Python API (which can be used without having ROS at all). -ROS wiki documentation: `axis_camera`_. +Please see the documentation located here: -This driver is under active development. Its ROS interfaces are -relatively stable, but may still change. +http://wiki.ros.org/axis_camera (ROS API) -There is no released code API. - -**Warning**:: - - The master branch normally contains code being tested for the next - ROS release. It does not always work with previous ROS distributions. - Sometimes, it may not work at all. - -Each official release is tagged in the repository. The `change -history`_ describes every version. +http://docs.ros.org/indigo/api/axis_camera/html/ (Python API) .. _`Axis network camera`: http://www.axis.com/products/video/camera/index.htm -.. _`change history`: https://github.com/clearpathrobotics/axis_camera/blob/master/CHANGELOG.rst .. _`axis_camera`: http://ros.org/wiki/axis_camera -.. _ROS: http://ros.org +.. _ROS: http://ros.org \ No newline at end of file diff --git a/cfg/Camera.cfg b/cfg/Camera.cfg new file mode 100755 index 0000000..215218c --- /dev/null +++ b/cfg/Camera.cfg @@ -0,0 +1,24 @@ +#!/usr/bin/env python +PACKAGE = "axis_camera" + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +gen.add("autofocus", bool_t, 0, "Autofocus", True) +gen.add("focus", int_t, 0, "Focus", 5000, 1, 9999) + +gen.add("brightness", int_t, 0, "Brightness", 5000, 1, 9999) + +gen.add("autoiris", bool_t, 0, "Auto iris", True) +gen.add("iris", int_t, 0, "Iris", 5000, 1, 9999) + +gen.add("backlight", bool_t, 0, "Backlight compensation (only with autoiris on)", False) + +auto_on_off_enum = gen.enum([gen.const("auto", str_t, "auto", "auto (only with autoiris on)"), + gen.const("on", str_t, "on", "on"), + gen.const("off", str_t, "off", "off")], + "IR Cut filter") +gen.add("ircutfilter", str_t, 0, "Infrared cut filter", "auto", edit_method=auto_on_off_enum) + +exit(gen.generate(PACKAGE, "axis_driver", "Camera")) diff --git a/cfg/PTZ.cfg b/cfg/PTZ.cfg index fbe4850..c25e45d 100755 --- a/cfg/PTZ.cfg +++ b/cfg/PTZ.cfg @@ -8,7 +8,7 @@ gen = ParameterGenerator() #gen.add("speed_control", bool_t, 0, "Speed control (true) or absolute position control (false)", False) gen.add("autofocus", bool_t, 0, "Autofocus", True) gen.add("pan", double_t, 0, "Pan value in degrees (or percent in absolute mode)", 0, -180, 180) -gen.add("tilt", double_t, 0, "Tilt value in degrees (or percent in absolute mode)", -45, -90, 0) +gen.add("tilt", double_t, 0, "Tilt value in degrees (or percent in absolute mode)", 0, -180, 180) gen.add("zoom", double_t, 0, "Zoom value", 1, 1, 9999) gen.add("focus", double_t, 0, "Focus", 1, 1, 9999) gen.add("brightness", double_t, 0, "Brightness", 1, 1, 9999) diff --git a/cfg/VideoStream.cfg b/cfg/VideoStream.cfg new file mode 100755 index 0000000..a88d5b4 --- /dev/null +++ b/cfg/VideoStream.cfg @@ -0,0 +1,20 @@ +#!/usr/bin/env python +PACKAGE = "axis_camera" + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +gen.add("use_color", bool_t, 0, "Use color image (not B/W)", True) +gen.add("compression", int_t, 0, "Compression level", 0, 0, 100) +gen.add("fps", int_t, 0, "FPS", 24, 1, 30) + +# The resolution enum is filled with values using dynamic_reconfigure_tools.change_enum_items, so that it only offers +# the resolutions supported by the camera in the Properties.Image.Resolution AXIS API parameter. +# This is kind of a hack, but it works at least for ROS and Python APIs (not sure about C++). +resolution_enum = gen.enum([gen.const("4CIF", str_t, "704x576", "4CIF (704x576)")], "Resolution") +gen.add("resolution", str_t, 0, "Image resolution", "704x576", edit_method=resolution_enum) + +gen.add("use_square_pixels", bool_t, 0, "Stretch video to fit square pixels", True) + +exit(gen.generate(PACKAGE, "axis_driver", "VideoStream")) diff --git a/conf.py b/conf.py deleted file mode 100644 index 1713534..0000000 --- a/conf.py +++ /dev/null @@ -1,250 +0,0 @@ -# -*- coding: utf-8 -*- -# -# axis_camera documentation build configuration file, created by -# sphinx-quickstart on Wed Apr 25 16:01:20 2012. -# -# This file is execfile()d with the current directory set to its containing dir. -# -# Note that not all possible configuration values are present in this -# autogenerated file. -# -# All configuration values have a default; values that are commented out -# serve to show the default. - -import sys, os - -# If extensions (or modules to document with autodoc) are in another directory, -# add these directories to sys.path here. If the directory is relative to the -# documentation root, use os.path.abspath to make it absolute, like shown here. - -#sys.path.insert(0, os.path.abspath('./src')) - -# -- General configuration ----------------------------------------------------- - -# If your documentation needs a minimal Sphinx version, state it here. -#needs_sphinx = '1.0' - -# Add any Sphinx extension module names here, as strings. They can be extensions -# coming with Sphinx (named 'sphinx.ext.*') or your custom ones. -extensions = ['sphinx.ext.autodoc', 'sphinx.ext.intersphinx', 'sphinx.ext.todo', 'sphinx.ext.viewcode'] - -# List automatically-documented module members in source code order. -autodoc_member_order = 'bysource' - -# Add any paths that contain templates here, relative to this directory. -templates_path = ['_templates'] - -# The suffix of source filenames. -source_suffix = '.rst' - -# The encoding of source files. -#source_encoding = 'utf-8-sig' - -# The master toctree document. -master_doc = 'index' - -# General information about the project. -project = u'axis_camera' -copyright = u'2012, Ryan Gariepy' - -# The version info for the project you're documenting, acts as replacement for -# |version| and |release|, also used in various other places throughout the -# built documents. -# -# The short X.Y version. -version = '0.1' -# The full version, including alpha/beta/rc tags. -release = '0.1.0' - -# The language for content autogenerated by Sphinx. Refer to documentation -# for a list of supported languages. -#language = None - -# There are two options for replacing |today|: either, you set today to some -# non-false value, then it is used: -#today = '' -# Else, today_fmt is used as the format for a strftime call. -#today_fmt = '%B %d, %Y' - -# List of patterns, relative to source directory, that match files and -# directories to ignore when looking for source files. -exclude_patterns = [] - -# The reST default role (used for this markup: `text`) to use for all documents. -#default_role = None - -# If true, '()' will be appended to :func: etc. cross-reference text. -#add_function_parentheses = True - -# If true, the current module name will be prepended to all description -# unit titles (such as .. function::). -#add_module_names = True - -# If true, sectionauthor and moduleauthor directives will be shown in the -# output. They are ignored by default. -#show_authors = False - -# The name of the Pygments (syntax highlighting) style to use. -pygments_style = 'sphinx' - -# A list of ignored prefixes for module index sorting. -#modindex_common_prefix = [] - - -# -- Options for HTML output --------------------------------------------------- - -# The theme to use for HTML and HTML Help pages. See the documentation for -# a list of builtin themes. -html_theme = 'default' - -# Theme options are theme-specific and customize the look and feel of a theme -# further. For a list of options available for each theme, see the -# documentation. -#html_theme_options = {} - -# Add any paths that contain custom themes here, relative to this directory. -#html_theme_path = [] - -# The name for this set of Sphinx documents. If None, it defaults to -# " v documentation". -#html_title = None - -# A shorter title for the navigation bar. Default is the same as html_title. -#html_short_title = None - -# The name of an image file (relative to this directory) to place at the top -# of the sidebar. -#html_logo = None - -# The name of an image file (within the static path) to use as favicon of the -# docs. This file should be a Windows icon file (.ico) being 16x16 or 32x32 -# pixels large. -#html_favicon = None - -# Add any paths that contain custom static files (such as style sheets) here, -# relative to this directory. They are copied after the builtin static files, -# so a file named "default.css" will overwrite the builtin "default.css". -html_static_path = ['_static'] - -# If not '', a 'Last updated on:' timestamp is inserted at every page bottom, -# using the given strftime format. -#html_last_updated_fmt = '%b %d, %Y' - -# If true, SmartyPants will be used to convert quotes and dashes to -# typographically correct entities. -#html_use_smartypants = True - -# Custom sidebar templates, maps document names to template names. -#html_sidebars = {} - -# Additional templates that should be rendered to pages, maps page names to -# template names. -#html_additional_pages = {} - -# If false, no module index is generated. -#html_domain_indices = True - -# If false, no index is generated. -#html_use_index = True - -# If true, the index is split into individual pages for each letter. -#html_split_index = False - -# If true, links to the reST sources are added to the pages. -#html_show_sourcelink = True - -# If true, "Created using Sphinx" is shown in the HTML footer. Default is True. -#html_show_sphinx = True - -# If true, "(C) Copyright ..." is shown in the HTML footer. Default is True. -#html_show_copyright = True - -# If true, an OpenSearch description file will be output, and all pages will -# contain a tag referring to it. The value of this option must be the -# base URL from which the finished HTML is served. -#html_use_opensearch = '' - -# This is the file name suffix for HTML files (e.g. ".xhtml"). -#html_file_suffix = None - -# Output file base name for HTML help builder. -htmlhelp_basename = 'axis_camera_doc' - - -# -- Options for LaTeX output -------------------------------------------------- - -latex_elements = { -# The paper size ('letterpaper' or 'a4paper'). -#'papersize': 'letterpaper', - -# The font size ('10pt', '11pt' or '12pt'). -#'pointsize': '10pt', - -# Additional stuff for the LaTeX preamble. -#'preamble': '', -} - -# Grouping the document tree into LaTeX files. List of tuples -# (source start file, target name, title, author, documentclass [howto/manual]). -latex_documents = [ - ('index', 'axis_camera.tex', u'ROS Axis camera driver.', - u'Ryan Gariepy', 'manual'), -] - -# The name of an image file (relative to this directory) to place at the top of -# the title page. -#latex_logo = None - -# For "manual" documents, if this is true, then toplevel headings are parts, -# not chapters. -#latex_use_parts = False - -# If true, show page references after internal links. -#latex_show_pagerefs = False - -# If true, show URL addresses after external links. -#latex_show_urls = False - -# Documents to append as an appendix to all manuals. -#latex_appendices = [] - -# If false, no module index is generated. -#latex_domain_indices = True - - -# -- Options for manual page output -------------------------------------------- - -# One entry per manual page. List of tuples -# (source start file, name, description, authors, manual section). -man_pages = [ - ('index', 'axis_camera', u'ROS Python Axis camera driver.', - [u'Ryan Gariepy'], 1) -] - -# If true, show URL addresses after external links. -#man_show_urls = False - - -# -- Options for Texinfo output ------------------------------------------------ - -# Grouping the document tree into Texinfo files. List of tuples -# (source start file, target name, title, author, -# dir menu entry, description, category) -texinfo_documents = [ - ('index', 'axis_camera', u'axis_camera Documentation', - u'Ryan Gariepy', 'axis_camera', 'ROS Axis camera driver.', - 'Miscellaneous'), -] - -# Documents to append as an appendix to all manuals. -#texinfo_appendices = [] - -# If false, no module index is generated. -#texinfo_domain_indices = True - -# How to display URL addresses: 'footnote', 'no', or 'inline'. -#texinfo_show_urls = 'footnote' - - -# Example configuration for intersphinx: refer to the Python standard library. -intersphinx_mapping = {'http://docs.python.org/': None} diff --git a/diag.yaml b/diag.yaml new file mode 100644 index 0000000..9f4ed39 --- /dev/null +++ b/diag.yaml @@ -0,0 +1,13 @@ +analyzers: + axis_camera: + type: diagnostic_aggregator/AnalyzerGroup + path: Axis Camera + analyzers: + video: + type: diagnostic_aggregator/GenericAnalyzer + path: Video Stream + find_and_remove_prefix: 'axis/axis:' + ptz: + type: diagnostic_aggregator/GenericAnalyzer + path: PTZ Control and Position + find_and_remove_prefix: 'axis/axis_ptz:' diff --git a/doc/axis.rst b/doc/axis.rst new file mode 100644 index 0000000..eb1b388 --- /dev/null +++ b/doc/axis.rst @@ -0,0 +1,7 @@ +axis module +=========== + +.. automodule:: axis + :members: + :undoc-members: + :show-inheritance: diff --git a/doc/axis_camera.rst b/doc/axis_camera.rst new file mode 100644 index 0000000..e78514f --- /dev/null +++ b/doc/axis_camera.rst @@ -0,0 +1,42 @@ +axis_camera package +=================== + +camera_control +-------------- + +.. automodule:: axis_camera.camera_control + :members: + :undoc-members: + :show-inheritance: + +dynamic_reconfigure_server2 +--------------------------- + +.. automodule:: axis_camera.dynamic_reconfigure_server2 + :members: + :undoc-members: + :show-inheritance: + +position_streaming +------------------ + +.. automodule:: axis_camera.position_streaming + :members: + :undoc-members: + :show-inheritance: + +vapix +----- + +.. automodule:: axis_camera.vapix + :members: + :undoc-members: + :show-inheritance: + +video_streaming +--------------- + +.. automodule:: axis_camera.video_streaming + :members: + :undoc-members: + :show-inheritance: diff --git a/doc/axis_camera.wiki b/doc/axis_camera.wiki new file mode 100644 index 0000000..542899e --- /dev/null +++ b/doc/axis_camera.wiki @@ -0,0 +1,428 @@ +<> + +== Overview == + +ROS camera driver for [[http://www.axis.com/products/video/camera/index.htm|Axis network cameras]] and probably other cameras supporting the VAPIX API. + +It provides both ROS and Python APIs. + +This wiki page describes the ROS API and usage. +For Python API and usage, please go to [[http://docs.ros.org/indigo/api/axis_camera/html/python|the Python API page]]. + +''This driver is under active development. Its interfaces have undergone a complete rewrite recently (but the new version should be backwards compatible).'' + +<> + +== Report a Bug == +https://github.com/clearpathrobotics/axis_camera/issues + +== Basics == + +The driver consists of two basic nodes - one for serving and controlling the video stream, and the other for controlling the pan-tilt-zoom capabilities as well as adjusting focus, iris, brightness, backlight compensation and automatic IR filter. + +The nodes are controlled using a set of ''dynamic_reconfigurable'' parameters (see below for their description). +The PTZ control node is also commanded by posting to any of its topics. + +''There is also an experimental nodelet for video processing utilizing the [[gscam]] plugin.'' + +''Before using this driver's PTZ capabilities, make sure you've allowed anonymous PTZ control in the camera settings +(or provide a username and password of a user with operator privileges).'' + +== Simple Usage == +The `roscore` must already be running before any of these example commands. + +While you can run the driver in the ROS root namespace, the image pipeline prefers running each camera in its own subordinate namespace. These examples use the `/axis` namespace. With multiple cameras, use something unique to the device, like the camera name. + +=== Running the Driver === +Pass the network host name of the camera on the command line, and a username/password if needed. This example uses the [[http://en.wikipedia.org/wiki/Zero_configuration_networking|zeroconf]] local [[http://en.wikipedia.org/wiki/Multicast_DNS|mDNS]] address, alternatively one could provide the static IP address for which the camera is configured. + +{{{ + $ roslaunch axis_camera axis.launch hostname:=axis-00408c8ae301.local +}}} +This publishes two topics: `/axis/camera_info` and `/axis/image_raw/compressed`. + +==== axis.launch arguments ==== + +- ''camera_name'': Name of the camera. Is used as a namespace for all published topics (default value: axis) + +- ''hostname'': Address of the camera (default value: 192.168.0.90) + +- ''enable_theora'': If set to 1, also the RAW and Theora versions of the image stream will be published (default value: 0) + +- ''enable_ptz'': If set to 1, start the PTZ node and allow PTZ control (default value: 0) + +- ''enable_ptz_teleop'': If set to 1, enable teleoperation of the camera using keyboard (default value: 0) + +- ''state_publishing_frequency'': The frequency at which the PTZ state will be published (default value: 50) + +- ''run_rviz'': If set to 1, run RViz displaying the camera model (default value: 0) + +- ''publish_tf'': If set to 1, publish TF for the camera (default value: 1) + +- ''use_standalone_model'': If set to 1, RViz will use a standalone model of the camera (default value: 1) + +=== Video stream === + +==== Viewing the compressed Image ==== +To see the compressed image, run [[image_view]] in another terminal this way: + +{{{ + $ rosrun image_view image_view image:=/axis/image_raw compressed +}}} + +==== Rectifying the Image ==== +Wide-angle network camera lenses generally exhibit significant intrinsic distortion. For robotics work, it is very helpful to calibrate each camera and use [[image_proc]] to provide rectified output. + +Since the driver produces compressed motion JPEG, and `image_proc` expects raw <> data, an extra argument is needed in the driver launch to publish a raw image stream: + +{{{ + $ roslaunch axis_camera axis.launch hostname:=axis-00408c8ae301.local enable_theora:=1 +}}} + +The argument name ''enable_theora'' may sound a bit confusing, but it actually means that an image_transport/republish node will be started that converts the source MJPEG stream to both a raw stream and a Theora stream. + +After that, open another terminal and run image_proc in the usual way: + +{{{ + $ ROS_NAMESPACE=axis rosrun image_proc image_proc _image_raw:=_image_raw_out +}}} +''If you know how to run image_proc directly on the compressed image stream, please open an issue to correct this documentation.'' + +==== Viewing Rectified Images ==== +To see the rectified color image, run [[image_view]] in another terminal this way: + +{{{ + $ rosrun image_view image_view image:=/axis/image_rect_color +}}} + +==== Calibrating the Camera ==== +To calibrate an Axis network camera, run the driver as shown above: + +{{{ + $ roslaunch axis_camera axis.launch hostname:=axis-00408c8ae301.local enable_theora:=1 +}}} +Then, in a second terminal, run [[camera_calibration]]: + +{{{ + $ rosrun camera_calibration cameracalibrator.py --size 8x6 --square 0.108 \ + image:=/axis/image_raw_out camera:=/axis +}}} +Then, follow the instructions in the [[http://www.ros.org/wiki/camera_calibration/Tutorials/MonocularCalibration|Monocular Camera Calibration tutorial]]. + +The resulting calibration parameters will be stored in `file://${ROS_HOME}/camera_info/${NAME}.yaml`, which resolves to `~/.ros/camera_info/axis_00408c8ae301_local.yaml` in this example (assuming $ROS_HOME points to the default `~/.ros` directory). The next time the driver runs on the same machine it should automatically pick up the existing calibration information in that same location. + +You can store the calibration elsewhere by setting `~camera_info_url` appropriately for the driver. For example, to store it in a package named `my_calibrations`, append this to the driver's argument list: + +{{{ +_camera_info_url:=package://my_calibrations/info/${NAME}.yaml +}}} +See [[camera_info_manager_py]] for details. + +==== Experimental nodelet ==== + +If you need to process the video inside a nodelet, there is an experimental implementation, which can be run by: + +{{{ +$ roslaunch axis_camera axis_gscam.launch hostname:=axis-00408c8ae301.local +}}} + +=== Using the PTZ node === +In order to use the PTZ node you need to enable anonymous PTZ control login in + +{{{ +http://IP_ADDRESS_OF_YOUR_CAMERA -> Setup -> Basic Setup -> Users +}}} + +or provide username/password of a user with operator privileges. + +After that run + +{{{ +roslaunch axis_camera axis.launch hostname:=axis-00408c8ae301.local enable_ptz:=1 [_username:=user _password:=pass] +}}} + +==== Absolute positioning ==== + +To point the camera to a specific position, publish to any of the absolute positioning topics: + +{{{ +rostopic pub -1 /axis/control/pan_tilt_zoom/absolute axis_camera/PTZ "{pan: 20, tilt: 20, zoom: 5000}" +}}} + +All ROS API commands use degrees, not radians. + +==== Relative positioning ==== + +To move the camera by a given amount from its current position, publish to any of the relative positioning topics: + +{{{ +rostopic pub -1 /axis/control/pan_tilt_zoom/relative axis_camera/PTZ "{pan: -20, tilt: 0, zoom: 200}" +}}} + +==== Velocity control ==== + +To command the camera with velocities instead of just positions, publish to the velocity topics. +Any subsequent call to absolute/relative positioning will clear the velocity command. + +{{{ +rostopic pub -1 /axis/control/pan_tilt_zoom/velocity axis_camera/PTZ "{pan: -20, tilt: 0, zoom: -10}" +}}} + +==== Camera mechanics control ==== + +Similarly to the PTZ commands above, you can control focus, iris, image brightness, backlight compensation and automatic IR cut filter. + +==== Transforms ==== + +The camera publishes 3 tf frames: ''axis_stand'', ''axis_pan_head'' and ''axis_tilt_head''. These correspond to the Axis 214 PTZ model. In a future release, there should be a more versatile way allowing to also use other camera models. + +== Dynamic reconfigure == + +The following parameters can be changed via ''dynamic_recofigure'': + +- namespace ''axis'' + + - every parameter change from this namespace causes all possibly open video streams to reconnect to get a new video stream with the updated parameters. + + - ''use_color'', ''compression'', ''fps'', ''resolution'', ''use_square_pixels''. + +- namespace ''axis_ptz_driver'' + + - ''autofocus'', ''focus'', ''brightness'', ''autoiris'', ''iris'', ''backlight'', ''ircutfilter''. + +== ROS API == +{{{#!clearsilver CS/NodeAPI +node.0 { +name=axis_driver +desc=Axis network camera video stream driver. +pub{ +0.name=axis/image_raw/compressed +0.type=sensor_msgs/CompressedImage +0.desc=A stream of compressed images from the camera in motion JPEG format. The topic's name *image_raw* is confusing, because it serves compressed images, but to retain backwards compatibility with the old driver version, it hasn't been changed. +1.name=axis/camera_info +1.type=sensor_msgs/CameraInfo +1.desc=Camera intrinsics for images published on `image_raw` with matching timestamps and frame IDs. If CameraInfo calibration is not available or is incompatible with the current `video_mode`, uncalibrated data will be provided instead. +} +srv{ +0.name=axis/take_snapshot +0.type=axis_camera/TakeSnapshot +0.desc=Take a snapshot from the camera and return it as a `sensor_msgs/CompressedImage` +} +param { +0.name=hostname +0.default= 192.168.0.90 +0.type=str +0.desc=Network name or address of the camera. +1.name=username +1.default= +1.type=str +1.desc=User name for accessing this camera. If empty, anonymous usage will be tried. +2.name=password +2.default= +2.type=str +2.desc=Password for accessing this camera. If empty, no password is used. +3.name=width +3.default=704 +3.type=int +3.desc=Requested image width. Must be compatible with the CIF standard. Deprecated in favor of the `resolution_name` parameter. +4.name=height +4.default=576 +4.type=int +4.desc=Requested image height. Must be compatible with the CIF standard. Deprecated in favor of the `resolution_name` parameter. +5.name=frame_id +5.default= axis_camera +5.type=str +5.desc=ROS transform frame of reference. +6.name=camera_info_url +6.type=str +6.default="" +6.desc=URL containing camera calibration information. see: [[camera_info_manager_py#URL_Names|camera_info_manager_py]]. +7.name=use_encrypted_password +7.type=bool +7.default=False +7.desc=Password encryption is a new feature of some Axis cameras. If True, send the password in encrypted form. +8.name=camera_id +8.type=int +8.default=1 +8.desc=Id of the camera in case a multi-camera system is used. Numbers 1 to 4. +9.name=auto_wakeup_camera +9.type=bool +9.default=True +9.desc=The camera might fall asleep after some idle time. If True, the driver will try to wake the camera up. +10.name=resolution +10.type=str +10.default=704x576 +10.desc=Dimensions of the image in the form "WidthxHeight". +11.name=compression +11.type=int +11.default=0 +11.desc=Compression of the image (0 - no compression, 100 - max compression). This parameter can be controlled via `dynamic_reconfigure`. +12.name=fps +12.type=int +12.default=24 +12.desc=The desired frames per second. This parameter can be controlled via `dynamic_reconfigure`. +13.name=use_color +13.type=bool +13.default=True +13.desc=If True, send a color stream, otherwise send only grayscale image. This parameter can be controlled via `dynamic_reconfigure`. +14.name=use_square_pixels +14.type=bool +14.default=False +14.desc=If True, the resolution will be stretched to match 1:1 pixels. By default, the pixels have a ratio of 11:12. This parameter can be controlled via `dynamic_reconfigure`. +} +} +node.1 { +name=axis_ptz_driver +desc=Axis network camera PTZ driver. +sub { +0.name=cmd +0.type=axis_camera/Axis +0.desc=Deprecated. Command absolute pan, tilt, zoom, brightness, iris, focus and autofocus. +1.name=mirror +1.type=std_msgs/Bool +1.desc=Deprecated. Whether to mirror camera controls or not. +2.name=control/pan_tilt_zoom/absolute +2.type=axis_camera/PTZ +2.desc=Command the PTZ unit with an absolute pose (pan/tilt unlimited (wraps around 360°), zoom limited to (1-9999)). +3.name=control/pan_tilt_zoom/relative +3.type=axis_camera/PTZ +3.desc=Command the PTZ unit with a relative pose shift (pan/tilt unlimited (wraps to -360° to 360°), zoom limited to (-9999 - 9999)). +4.name=control/pan_tilt_zoom/velocity +4.type=axis_camera/PTZ +4.desc=Command the PTZ unit velocity in terms of pan, tilt and zoom (all limited to (-100 - 100)). +5.name=control/pan_tilt/absolute +5.type=axis_camera/PTZ +5.desc=Command the PTZ unit with an absolute pose, ignoring zoom (pan/tilt unlimited (wraps around 360°)). +6.name=control/pan_tilt/relative +6.type=axis_camera/PTZ +6.desc=Command the PTZ unit with a relative pose shift, ignoring zoom (pan/tilt unlimited (wraps to -360° to 360°)). +7.name=control/pan_tilt/velocity +7.type=axis_camera/PTZ +7.desc=Command the PTZ unit velocity in terms of pan and tilt (all limited to (-100 - 100)). +8.name=control/pan/absolute +8.type=std_msgs/Float32 +8.desc=Command the PTZ unit with absolute pan (unlimited, wraps around 360°). +9.name=control/tilt/absolute +9.type=std_msgs/Float32 +9.desc=Command the PTZ unit with absolute tilt (unlimited, wraps around 360°). +10.name=control/zoom/absolute +10.type=std_msgs/Int32 +10.desc=Command the PTZ unit with absolute zoom (1-9999). +11.name=control/pan/relative +11.type=std_msgs/Float32 +11.desc=Command the PTZ unit with a relative pan change (unlimited, wraps to -360° to 360°). +12.name=control/tilt/relative +12.type=std_msgs/Float32 +12.desc=Command the PTZ unit with a relative tilt change (unlimited, wraps to -360° to 360°). +13.name=control/zoom/relative +13.type=std_msgs/Int32 +13.desc=Command the PTZ unit with a relative zoom change (-9999 - 9999). +14.name=control/pan/velocity +14.type=std_msgs/Int32 +14.desc=Command the PTZ unit pan velocity (-100 - 100). +15.name=control/tilt/velocity +15.type=std_msgs/Int32 +15.desc=Command the PTZ unit tilt velocity (-100 - 100). +16.name=control/zoom/velocity +16.type=std_msgs/Int32 +16.desc=Command the PTZ unit zoom velocity (-100 - 100). +17.name=control/look_at +17.type=axis_camera/PointInRectangle +17.desc=Given x/y coordinates and the pixel width/height of the image, the camera is moved so that the point clicked at (x/y) will be the new optical center. +18.name=control/camera/focus/auto +18.type=std_msgs/Bool +18.desc=Command the camera to use/stop using autofocus. +19.name=control/camera/focus/absolute +19.type=std_msgs/Int32 +19.desc=Set focus to the desired value (1-9999). Implies turning off autofocus. +20.name=control/camera/focus/relative +20.type=std_msgs/Int32 +20.desc=Add the desired amount to the focus value (-9999 - 9999). Implies turning off autofocus. +21.name=control/camera/focus/velocity +21.type=std_msgs/Int32 +21.desc=Set the focus "speed" (-100 - 100). Active until another focus command is issued. Implies turning off autofocus. +22.name=control/camera/iris/auto +22.type=std_msgs/Bool +22.desc=Command the camera to use/stop using auto iris adjustment. Autoiris is required for auto IR filter. +23.name=control/camera/iris/absolute +23.type=std_msgs/Int32 +23.desc=Set iris to the desired value (1-9999). Implies turning off autoiris. +24.name=control/camera/iris/relative +24.type=std_msgs/Int32 +24.desc=Add the desired amount to the iris value (-9999 - 9999). Implies turning off autoiris. +25.name=control/camera/iris/velocity +25.type=std_msgs/Int32 +25.desc=Set the iris "speed" (-100 - 100). Active until another focus command is issued. Implies turning off autoiris. +26.name=control/camera/brightness/absolute +26.type=std_msgs/Int32 +26.desc=Set brightness to the desired value (1-9999). Has no effect on 214 PTZ. +27.name=control/camera/brightness/relative +27.type=std_msgs/Int32 +27.desc=Add the desired amount to the brightness value (-9999 - 9999). Has no effect on 214 PTZ. +28.name=control/camera/brightness/velocity +28.type=std_msgs/Int32 +28.desc=Set the brightness "speed" (-100 - 100). Has no effect on 214 PTZ. +29.name=control/camera/backlight_compensation +29.type=std_msgs/Bool +29.desc=Command the camera to use/stop using backlight compensation (requires autoiris=on set before). +30.name=control/camera/ir_cut_filter/auto +30.type=std_msgs/Bool +30.desc=Command the camera to use auto infrared filter (requires autoiris=on set before). +31.name=control/camera/ir_cut_filter/use +31.type=std_msgs/Bool +31.desc=Command the camera to use/stop using infrared filter. Turns off auto IR filter. +} +pub{ +0.name=camera/joint_states +0.type=sensor_msgs/JointStates +0.desc=Pose of the camera (joint names are ''axis_pan_j'' and ''axis_tilt_j'') +1.name=camera/ptz +1.type=axis_camera/PTZ +1.desc=Pose of the camera. +} +prov_tf{ +0.from=axis_stand +0.to=axis_pan_head +0.desc=Transform between the camera stand and the panning head. +1.from=axis_pan_head +1.to=axis_tilt_head +1.desc=Transform between the panning head and the tilt joint. +} +param{ +0.name=autofocus +0.default=True +0.type=bool +0.desc=Whether to use autofocus. +1.name=focus +1.default=5000 +1.type=int +1.desc=The desired value of focus (0-9999). +2.name=brightness +2.default=5000 +2.type=int +2.desc=The desired value of brightness (0-9999). Has no effect on some models. +3.name=autoiris +3.default=True +3.type=bool +3.desc=Whether to use autoiris. +4.name=iris +4.default=5000 +4.type=int +4.desc=The desired value of iris (0-9999). +5.name=backlight +5.default=True +5.type=bool +5.desc=Whether to use backlight compensation. +6.name=ircutfilter +6.default=auto +6.type=str +6.desc=Whether to use IR cut filter (values "auto", "on", "off"). +} +}}} + +Parameters are resolved starting with the driver's private namespace and going up to global parameters. +If desired, they may be defined in some containing namespace. +That is useful for sharing parameters between the video and PTZ nodes. + +## AUTOGENERATED DON'T DELETE +## CategoryStack \ No newline at end of file diff --git a/doc/axis_ptz.rst b/doc/axis_ptz.rst new file mode 100644 index 0000000..105be07 --- /dev/null +++ b/doc/axis_ptz.rst @@ -0,0 +1,7 @@ +axis_ptz module +=============== + +.. automodule:: axis_ptz + :members: + :undoc-members: + :show-inheritance: diff --git a/doc/changelog.rst b/doc/changelog.rst new file mode 100644 index 0000000..4d7817a --- /dev/null +++ b/doc/changelog.rst @@ -0,0 +1 @@ +.. include:: ../CHANGELOG.rst \ No newline at end of file diff --git a/doc/conf.py b/doc/conf.py new file mode 100644 index 0000000..664a244 --- /dev/null +++ b/doc/conf.py @@ -0,0 +1,108 @@ +# -*- coding: utf-8 -*- +# +# axis_camera documentation build configuration file, created by +# sphinx-quickstart on Wed Apr 25 16:01:20 2012. +# +# This file is execfile()d with the current directory set to its containing dir. +# +# Note that not all possible configuration values are present in this +# autogenerated file. +# +# All configuration values have a default; values that are commented out +# serve to show the default. + +# ROSifying the docs + +import os, sys +import catkin_pkg.package +catkin_dir = os.path.dirname(os.path.dirname(os.path.abspath(__file__))) +catkin_package = catkin_pkg.package.parse_package(os.path.join(catkin_dir, catkin_pkg.package.PACKAGE_MANIFEST_FILENAME)) + +sys.path.insert(0, os.path.abspath('..' + os.path.sep + 'nodes')) + +# -- General configuration ----------------------------------------------------- + +extensions = ['sphinx.ext.autodoc', 'sphinx.ext.intersphinx', 'sphinx.ext.todo', 'sphinx.ext.viewcode'] + +# List automatically-documented module members in source code order. +autodoc_member_order = 'bysource' + +# Add any paths that contain templates here, relative to this directory. +templates_path = ['_templates'] + +# The suffix of source filenames. +source_suffix = '.rst' + +# The master toctree document. +master_doc = 'index' + +# General information about the project. +project = catkin_package.name +copyright = u'2012, ' + ', '.join([str(author) for author in catkin_package.authors]) + +# The version info for the project you're documenting, acts as replacement for +# |version| and |release|, also used in various other places throughout the +# built documents. +# +version = catkin_package.version +release = catkin_package.version + +# List of patterns, relative to source directory, that match files and +# directories to ignore when looking for source files. +exclude_patterns = [] + +# The name of the Pygments (syntax highlighting) style to use. +pygments_style = 'sphinx' + + +# -- Options for HTML output --------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. See the documentation for +# a list of builtin themes. +html_theme = 'default' + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +html_static_path = ['_static'] + +# Output file base name for HTML help builder. +htmlhelp_basename = 'axis_camera_doc' + + +# -- Options for manual page output -------------------------------------------- + +# One entry per manual page. List of tuples +# (source start file, name, description, authors, manual section). +man_pages = [ + ('index', 'axis_camera', u'ROS Python Axis camera driver.', + [u'Ryan Gariepy'], 1) +] + +# If true, show URL addresses after external links. +#man_show_urls = False + + +# -- Options for Texinfo output ------------------------------------------------ + +# Grouping the document tree into Texinfo files. List of tuples +# (source start file, target name, title, author, +# dir menu entry, description, category) +texinfo_documents = [ + ('index', 'axis_camera', u'axis_camera Documentation', + u'Ryan Gariepy', 'axis_camera', 'ROS Axis camera driver.', + 'Miscellaneous'), +] + +# Documents to append as an appendix to all manuals. +#texinfo_appendices = [] + +# If false, no module index is generated. +#texinfo_domain_indices = True + +# How to display URL addresses: 'footnote', 'no', or 'inline'. +#texinfo_show_urls = 'footnote' + + +# Example configuration for intersphinx: refer to the Python standard library. +intersphinx_mapping = {'python': ('http://docs.python.org/2.7', None)} diff --git a/doc/index.rst b/doc/index.rst new file mode 100644 index 0000000..9d71367 --- /dev/null +++ b/doc/index.rst @@ -0,0 +1,72 @@ +axis_camera: ROS Axis PTZ cameras support +========================================= + +.. toctree:: + :hidden: + + axis_camera + axis + axis_ptz + changelog + +Overview +======== + +This ROS_ package provides an `Axis network camera`_ driver, written +in Python. It provides both a ROS API (via ROS topics and parameters) and Python API (which can be used without having ROS at all). + +The ROS API (topics, parameters, services) is documented on the ROS wiki: `axis_camera`_. + +This driver is under active development. Its interface has undergone a major rework towards better usability and versatility. +This rework was, however, done with backwards compatibility in mind. +The API might still change if some problems are found. + +Tested compatible ROS versions: + +- Indigo + +Tested compatible Axis camera models: + +- 214 PTZ +- P5512-E +- V5914 +- others should also work, because the VAPIX API should be supported on all Axis cameras + +**Warning**:: + + The master branch normally contains code being tested for the next + ROS release. It does not always work with previous ROS distributions. + Sometimes, it may not work at all. + +Each official release is tagged in the repository. The `change +history`_ describes every version. + +Python usage +------------ + +High-level API +************** + +In module ``axis_camera``, there are the classes ``ImageStreamingThread``, ``PositionStreamingThread`` and ``AxisCameraController``. Normally, they are started by the ROS nodes, but you can start them manually. + +Unfortunately, because of backwards compatibility, these classes take a node instance in their constructors, so you either have to use them with the ROS nodes running, or you could pass a duck-typed class with the required members. + +A future refactoring will probably completely split these threads from the ROS nodes. + +Low-level API +************* + +Class ``axis_camera.VAPIX`` provides a direct interface to the camera's HTTP VAPIX API. It is built so that it simplifies creating API commands, detects some error states and handles them. + +The class provides autodetection of the VAPIX version supported by the camera (either v2 or v3). So, basically, to get an instance of the API, call ``api = VAPIX.get_api_for_camera(hostname, username, password, camera_id, use_encrypted_password)``. + +The class methods are well documented, so please refer to that documentation. In the future, this documentation should be compiled as the standard ROS package Python documentation and available through docs.ros.org . + +This class can be used completely without ROS in other projects. It just uses two or three methods from the ``rospy`` module (mostly logging), so if you either edit the class or duck-type the rospy module and the required functions, you can happily use this Python interface from anywhere. In case you want to use this class without ROS, you don't need to build the package with ``catkin_make``. + + +.. _`Axis network camera`: http://www.axis.com/products/video/camera/index.htm +.. _`change history`: https://github.com/clearpathrobotics/axis_camera/blob/master/CHANGELOG.rst +.. _`axis_camera`: http://ros.org/wiki/axis_camera +.. _ROS: http://ros.org +.. _CIF: https://en.wikipedia.org/wiki/Common_Intermediate_Format diff --git a/doc/manifest.yaml b/doc/manifest.yaml new file mode 100644 index 0000000..2d51f5d --- /dev/null +++ b/doc/manifest.yaml @@ -0,0 +1,28 @@ +actions: [] +authors: Ryan Gariepy +brief: '' +bugtracker: https://github.com/ros-drivers/axis_camera/issues +depends: +- dynamic_reconfigure +- xacro +- std_msgs +- message_runtime +- sensor_msgs +- camera_info_manager_py +- python-catkin-pkg +- rospy +- tf +- message_generation +- catkin +description: "Python ROS drivers for accessing an Axis camera's MJPG stream. Also provides control for PTZ cameras." +license: BSD +maintainers: Sammy Pfeiffer +msgs: +- Axis +- PointInRectangle +- PTZ +package_type: package +repo_url: https://github.com/ros-drivers/axis_camera +srvs: +- TakeSnapshot +url: http://ros.org/wiki/axis_camera diff --git a/index.rst b/index.rst deleted file mode 100644 index de235e0..0000000 --- a/index.rst +++ /dev/null @@ -1,16 +0,0 @@ -camera_info_manager: ROS CameraInfo support for Python camera drivers -===================================================================== - -Contents: - -.. toctree:: - :maxdepth: 2 - - README - CHANGELOG - -Indices and tables -================== - -* :ref:`genindex` -* :ref:`modindex` diff --git a/launch/axis.launch b/launch/axis.launch index 06f53c3..5a999d5 100644 --- a/launch/axis.launch +++ b/launch/axis.launch @@ -1,16 +1,44 @@ - + + + + + + - - + + + + + + - + + + + + + + + + + + + + + + + + @@ -24,11 +52,14 @@ + + + + + + + + - diff --git a/launch/axis_standalone_view.rviz b/launch/axis_standalone_view.rviz new file mode 100644 index 0000000..60c61bf --- /dev/null +++ b/launch/axis_standalone_view.rviz @@ -0,0 +1,170 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /RobotModel1 + Splitter Ratio: 0.493289 + Tree Height: 286 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + axis_origin: + Alpha: 1 + Show Axes: false + Show Trail: false + axis_pan_head: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + axis_stand: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + axis_tilt_head: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: true + Marker Scale: 0.5 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + {} + Update Interval: 0 + Value: false + - Class: rviz/Image + Enabled: true + Image Topic: /axis/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: compressed + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: axis_origin + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 3.03029 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 1.44198 + Y: -1.37013 + Z: -0.0130588 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.0598001 + Target Frame: + Value: Orbit (rviz) + Yaw: 2.38675 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1056 + Hide Left Dock: false + Hide Right Dock: true + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000039000000399fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000001ad000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000001db000001e60000001600ffffff000000010000010f00000202fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000202000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003bfc0100000002fc000000000000073f000002f600fffffffa000000010200000002fb0000000800500061006e006f0000000000ffffffff0000000000000000fb0000000800540069006d006501000003700000003e0000003b00fffffffb0000000800540069006d00650100000000000004500000000000000000000003a90000039900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1855 + X: 65 + Y: 24 diff --git a/meshes/pan_head.dae b/meshes/pan_head.dae new file mode 100644 index 0000000..322bf99 --- /dev/null +++ b/meshes/pan_head.dae @@ -0,0 +1,191 @@ + + + + + Blender User + Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b + + 2015-09-11T13:28:52 + 2015-09-11T13:28:52 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.4521739 0.4521739 0.4521739 1 + + + 0.08695655 0.08695655 0.08695655 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + 1 0.473303 13.96725 0.4452555 0.4733032 12.57822 0.4452555 0.457648 14.93159 1 0.4139986 16.2114 0.4452555 0.3688202 17.03452 1 0.2878494 18.00092 0.4452555 0.216835 18.56233 1 0.1101417 19.04153 0.4452555 0.09256112 19.06828 1 0 19.18182 0.4452555 0 19.18182 1 -0.092561 19.06827 0.4452554 -0.120613 19.01907 1 -0.2043476 18.63162 0.4452555 -0.2999573 17.88835 1 -0.3584309 17.18262 0.4452711 -0.4609029 15.1256 1.000817 -0.4725031 14.46418 0.9238796 -0.3826833 1.909091 0.4440521 -0.3826277 1.909091 0.973109 -0.2583684 -0.09080684 0.4440876 0.7071533 1.909091 0.9999008 0.07981562 -0.09083753 0.9197019 0.3796221 -0.09075868 0.8222102 0.5620136 -0.09080213 0.7071068 0.7071068 1.909091 0.9995293 0.4429543 10.994 0.4452555 0.4383373 11.01142 0.002472281 0.9997565 -0.09090924 0.2745362 0.966081 -0.09090906 0.4727173 0.8843937 1.909093 0.6234245 0.7874069 -0.09090924 0.8314697 -0.5555702 -0.09090924 0.7650604 -0.6506558 1.909091 0.6506538 -0.7650604 -0.09090924 0.4578285 -0.8939037 1.909092 0.3081837 -0.9558849 -0.09090924 -0.002650022 -1.00842 1.909097 -1 0.473303 13.96725 -0.4452555 0.4733032 12.57822 -0.4452555 0.457648 14.93159 -1 0.4139986 16.2114 -0.4452555 0.3688202 17.03452 -1 0.2878494 18.00092 -0.4452555 0.216835 18.56233 -1 0.1101417 19.04153 -0.4452555 0.09256112 19.06828 -1 0 19.18182 -0.4452555 0 19.18182 -1 -0.092561 19.06827 -0.4452554 -0.120613 19.01907 -1 -0.2043476 18.63162 -0.4452555 -0.2999573 17.88835 -1 -0.3584309 17.18262 -0.4452711 -0.4609029 15.1256 -1.000817 -0.4725031 14.46418 -0.9238796 -0.3826833 1.909091 -0.4440521 -0.3826277 1.909091 -0.973109 -0.2583684 -0.09080684 -0.4440876 0.7071533 1.909091 -0.9999008 0.07981562 -0.09083753 -0.9197019 0.3796221 -0.09075868 -0.8222102 0.5620136 -0.09080213 -0.7071068 0.7071068 1.909091 -0.9995293 0.4429543 10.994 -0.4452555 0.4383373 11.01142 -0.002472281 0.9997565 -0.09090924 0 1.013883 1.90911 -0.2745362 0.966081 -0.09090906 -0.4727173 0.8843937 1.909093 -0.6234245 0.7874069 -0.09090924 -0.8314697 -0.5555702 -0.09090924 -0.7650604 -0.6506558 1.909091 -0.6506538 -0.7650604 -0.09090924 -0.4578285 -0.8939037 1.909092 -0.3081837 -0.9558849 -0.09090924 0.002650022 -1.00842 1.909097 0 -0.9999523 -0.09090924 + + + + + + + + + + 0.02555888 0.9996212 -0.01020741 -1 0 0 -1 2.51734e-7 1.20737e-7 -1 0 0 -0.9999998 4.1584e-4 9.47008e-5 -1 -6.71399e-6 -5.29372e-6 -1 2.35321e-7 1.91839e-7 -1 3.25704e-5 1.29269e-4 -1 -1.58175e-5 3.52996e-7 1 0 0 0.9659987 0.2584092 -0.008433043 0.9775488 -0.2104229 0.01098322 0.9999999 3.5908e-4 2.85582e-4 0.8818832 0.4713811 -0.00904411 0.4558079 0.8900345 -0.008813977 4.17412e-4 3.74635e-4 -0.9999998 0.9999997 7.76849e-4 -1.6624e-4 -2.32658e-4 -6.80338e-4 -0.9999998 -0.01665341 0.9998392 0.006651103 -0.0187447 0.9989335 0.04219514 -0.0271933 0.9947204 0.09895342 -0.01926964 0.9709534 0.2384916 0.005908071 0.775066 0.6318528 -0.01217865 -0.8033622 0.5953662 -0.03963762 -0.9868776 0.1565294 -0.03122687 -0.9978206 0.05812835 -0.02791732 -0.9995928 -0.005917549 0.9968731 -0.07897478 0.002620577 -1 -1.72197e-5 -7.27362e-7 -0.009028553 0.9997103 -0.02231031 9.01332e-7 2.63567e-6 -1 0.26417 0.9643856 0.0132122 0.6207116 -0.7839834 0.009338915 0.2413209 -0.970371 0.01201611 1 2.26951e-7 0 0.7495653 0.6619125 -0.004881024 0.0290513 -0.9986986 0.04191654 0.02969306 -0.9939553 0.1056945 0.04413098 0.9847695 0.1681714 0.01770925 0.9994943 0.0264129 0 -0.7751059 0.6318315 0.02698171 -0.9684041 0.2479223 1 -5.30993e-7 4.32842e-7 -1.15896e-4 -0.9999744 -0.007153153 0.9997288 -0.02242428 -0.00628674 0 0 -1 1.68731e-5 -1.78809e-5 1 0.02309316 0.9972586 0.07030004 0 0.7865596 0.6175146 -1.10102e-5 -8.9874e-5 -1 1 -5.34042e-7 4.09731e-7 0.6032362 0.7975338 0.006780862 0.8602544 -0.5098469 0.004324853 1.17992e-5 -6.99302e-6 1 1 1.83194e-7 -1.40551e-7 -0.007398366 0.9995368 0.02951991 -1.20095e-7 3.32666e-7 -1 0.9999997 8.76346e-4 2.3132e-5 0.1228377 0.992403 -0.006857573 -1 -1.709e-5 0 0.7570019 -0.6533859 -0.005927801 0.1415497 -0.9899231 -0.004003465 1.05314e-4 -1.30201e-7 -1 4.82693e-6 -2.35613e-4 -0.9999999 3.12927e-5 -1.64887e-5 1 0.7499802 0.6614427 -0.004823029 0.9027168 -0.4302116 -0.004521012 1.76687e-4 0.9995778 0.02905797 0 -1.14336e-5 1 4.26804e-5 0 1 -2.47043e-4 4.62234e-4 -0.9999998 2.33087e-5 -6.16106e-6 1 0 1.04763e-5 1 0.4867192 -0.8735085 -0.009346902 -0.02555888 0.9996212 -0.01020741 1 0 0 1 2.51734e-7 1.20737e-7 1 0 0 0.9999998 4.1584e-4 9.47008e-5 1 -6.71399e-6 -5.29372e-6 1 2.35321e-7 1.91839e-7 1 3.25704e-5 1.29269e-4 1 -1.58175e-5 3.52996e-7 -1 0 0 -0.9659988 0.2584092 -0.008433043 -0.9775488 -0.2104228 0.01098322 -0.9999999 3.5908e-4 2.85582e-4 -0.8818832 0.4713812 -0.00904411 -0.4558079 0.8900345 -0.008813977 -4.17413e-4 3.74635e-4 -0.9999999 -0.9999997 7.76849e-4 -1.6624e-4 2.32658e-4 -6.80338e-4 -0.9999998 0.01665341 0.9998392 0.006651103 0.0187447 0.9989335 0.04219514 0.0271933 0.9947204 0.09895342 0.01926964 0.9709534 0.2384916 -0.005908071 0.775066 0.6318528 0.01217865 -0.8033621 0.5953662 0.03963762 -0.9868776 0.1565294 0.03122687 -0.9978206 0.05812835 0.02791738 -0.9995928 -0.005917549 -0.9968731 -0.07897478 0.002620577 1 -1.72197e-5 -7.27362e-7 0.009028553 0.9997103 -0.02231031 -9.01332e-7 2.63567e-6 -1 -0.2641699 0.9643856 0.0132122 -0.6207116 -0.7839834 0.009338915 -0.2413209 -0.970371 0.01201611 -1 2.26951e-7 0 -0.7495653 0.6619125 -0.004881024 -0.0290513 -0.9986986 0.04191654 -0.02969306 -0.9939553 0.1056945 -0.04413098 0.9847695 0.1681714 -0.01770925 0.9994943 0.0264129 0 -0.7751059 0.6318315 -0.02698171 -0.9684041 0.2479223 -1 -5.30993e-7 4.32842e-7 1.15895e-4 -0.9999744 -0.007153153 -0.9997288 -0.02242428 -0.00628674 0 0 -1 -1.68731e-5 -1.78809e-5 1 -0.02309316 0.9972586 0.07030004 0 0.7865595 0.6175146 1.10102e-5 -8.9874e-5 -1 -1 -5.34042e-7 4.09731e-7 -0.6032362 0.7975338 0.006780862 -0.8602544 -0.5098469 0.004324853 -1.17992e-5 -6.99303e-6 1 -1 1.83194e-7 -1.40551e-7 0.007398366 0.9995368 0.02951991 1.20095e-7 3.32666e-7 -1 -0.9999997 8.76346e-4 2.3132e-5 -0.1228377 0.992403 -0.006857573 1 -1.709e-5 0 -0.7570019 -0.6533859 -0.005927801 -0.1415497 -0.9899231 -0.004003465 -1.05314e-4 -1.30202e-7 -1 -4.82695e-6 -2.35613e-4 -0.9999999 -3.12927e-5 -1.64887e-5 1 -0.7499802 0.6614428 -0.004823029 -0.9027168 -0.4302117 -0.004521012 -1.76731e-4 0.9995777 0.02905797 0 -1.14336e-5 1 -4.26804e-5 0 1 2.47043e-4 4.62234e-4 -0.9999999 -2.33087e-5 -6.16106e-6 1 0 1.04763e-5 1 -0.4867193 -0.8735085 -0.009346902 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 26 0 1 0 6 1 14 1 12 1 12 2 8 2 6 2 14 3 6 3 4 3 19 4 16 4 27 4 16 5 14 5 4 5 12 6 10 6 8 6 27 7 21 7 19 7 27 8 16 8 1 8 15 9 3 9 5 9 22 10 23 10 26 10 20 11 26 11 18 11 15 12 17 12 3 12 23 13 24 13 26 13 29 14 30 14 31 14 22 15 28 15 23 15 17 16 26 16 0 16 24 17 28 17 31 17 0 18 1 18 2 18 3 19 2 19 4 19 5 20 4 20 6 20 7 21 6 21 8 21 7 22 8 22 10 22 10 23 12 23 11 23 12 24 14 24 13 24 14 25 16 25 15 25 17 26 16 26 19 26 22 27 26 27 20 27 16 28 4 28 2 28 26 29 27 29 1 29 31 30 28 30 29 30 67 31 30 31 29 31 33 32 35 32 34 32 35 33 37 33 36 33 5 34 13 34 15 34 24 35 25 35 26 35 15 36 16 36 17 36 13 37 14 37 15 37 7 38 5 38 6 38 3 39 0 39 2 39 9 40 10 40 11 40 11 41 12 41 13 41 7 42 9 42 11 42 18 43 17 43 19 43 18 44 26 44 17 44 77 45 32 45 34 45 33 46 37 46 35 46 5 47 3 47 4 47 9 48 7 48 10 48 20 49 28 49 22 49 11 50 13 50 7 50 31 51 30 51 25 51 18 52 33 52 32 52 18 53 37 53 33 53 5 54 7 54 13 54 21 55 27 55 26 55 77 56 34 56 36 56 17 57 0 57 3 57 29 58 28 58 67 58 1 59 16 59 2 59 32 60 33 60 34 60 36 61 37 61 77 61 28 62 20 62 77 62 28 63 24 63 23 63 21 64 30 64 67 64 31 65 25 65 24 65 20 66 18 66 32 66 25 67 21 67 26 67 21 68 25 68 30 68 21 69 67 69 19 69 20 70 32 70 77 70 67 71 37 71 19 71 19 72 37 72 18 72 34 73 35 73 36 73 38 74 39 74 64 74 44 75 50 75 52 75 50 76 44 76 46 76 52 77 42 77 44 77 57 78 65 78 54 78 54 79 42 79 52 79 50 80 46 80 48 80 65 81 57 81 59 81 65 82 39 82 54 82 53 83 43 83 41 83 60 84 64 84 61 84 58 85 56 85 64 85 53 86 41 86 55 86 61 87 64 87 62 87 68 88 70 88 69 88 60 89 61 89 66 89 55 90 38 90 64 90 62 91 70 91 66 91 38 92 40 92 39 92 41 93 42 93 40 93 43 94 44 94 42 94 45 95 46 95 44 95 45 96 48 96 46 96 48 97 49 97 50 97 50 98 51 98 52 98 52 99 53 99 54 99 55 100 57 100 54 100 60 101 58 101 64 101 54 102 40 102 42 102 64 103 39 103 65 103 70 104 68 104 66 104 67 105 68 105 69 105 72 106 73 106 74 106 74 107 75 107 76 107 43 108 53 108 51 108 62 109 64 109 63 109 53 110 55 110 54 110 51 111 53 111 52 111 45 112 44 112 43 112 41 113 40 113 38 113 47 114 49 114 48 114 49 115 51 115 50 115 45 116 49 116 47 116 56 117 57 117 55 117 56 118 55 118 64 118 77 119 73 119 71 119 72 120 74 120 76 120 43 121 42 121 41 121 47 122 48 122 45 122 58 123 60 123 66 123 49 124 45 124 51 124 70 125 63 125 69 125 56 126 71 126 72 126 56 127 72 127 76 127 43 128 51 128 45 128 59 129 64 129 65 129 77 130 75 130 73 130 55 131 41 131 38 131 68 132 67 132 66 132 39 133 40 133 54 133 71 134 73 134 72 134 75 135 77 135 76 135 66 136 77 136 58 136 66 137 61 137 62 137 59 138 67 138 69 138 70 139 62 139 63 139 58 140 71 140 56 140 63 141 64 141 59 141 59 142 69 142 63 142 59 143 57 143 67 143 58 144 77 144 71 144 67 145 57 145 76 145 57 146 56 146 76 146 73 147 75 147 74 147

+
+
+
+ + + + 1 0.4744526 13.27272 0.4452555 0.4744526 13.27273 1 0.465336 14.42553 0.4452555 0.465336 14.42553 1 0.438337 15.53404 0.4452555 0.438337 15.53404 1 0.3944929 16.55564 0.4452555 0.3944929 16.55564 1 0.3354886 17.45108 0.4452555 0.3354886 17.45108 1 0.2635917 18.18596 0.4452555 0.2635917 18.18596 1 0.1815651 18.73201 0.4452555 0.1815651 18.73201 1 0.09256112 19.06827 0.4452555 0.09256112 19.06828 1 0 19.18182 0.4452555 0 19.18182 1 -0.092561 19.06827 0.4452555 -0.092561 19.06828 1 -0.1815651 18.73201 0.4452555 -0.1815651 18.73201 1 -0.2635917 18.18596 0.4452555 -0.2635917 18.18596 1 -0.3354886 17.45108 0.4452555 -0.3354886 17.45108 1 -0.3944929 16.55564 0.4452555 -0.3944929 16.55564 1 -0.438337 15.53404 0.4452555 -0.438337 15.53404 1 -0.4653361 14.42553 0.4452555 -0.4653361 14.42553 1 -0.4744526 13.27272 0.4452555 -0.4744526 13.27272 1 -0.465336 12.11992 0.4452555 -0.465336 12.11992 1 -0.4383369 11.01141 0.4452555 4.58131e-7 7.363636 1 0.09256154 7.477179 1 0.1815656 7.81344 1 0.2635922 8.359501 1 0.335489 9.094374 1 0.3944932 9.989818 1 0.4383373 11.01142 0.4452555 0.4383373 11.01142 1 0.4653362 12.11993 0.4452555 0.4653362 12.11993 1 1 0.9090906 -1 1 0.9090908 1 0.9807853 1.104181 -1 0.9807853 1.104181 1 0.9238795 1.291774 -1 0.9238795 1.291774 1 0.8314696 1.464661 -0.9999999 0.8314696 1.464661 1 0.7071068 1.616197 1 0.5555702 1.74056 1 0.3826834 1.83297 1 0.1950902 1.889876 1 0 1.909091 1 -0.1950902 1.889876 1 -0.3826833 1.83297 1 -0.5555702 1.74056 -0.9999999 -0.5555702 1.740561 1 -0.7071068 1.616197 -0.9999998 -0.7071068 1.616198 1 -0.8314697 1.464661 -1 -0.8314697 1.464661 1 -0.9238796 1.291774 -1 -0.9238796 1.291774 1 -0.9807853 1.104181 -1 -0.9807853 1.104181 1 -1 0.9090903 -1 -1 0.9090904 -0.4578285 -0.8939037 1.909092 -0.3081837 -0.9558849 -0.09090924 0.002650022 -1.00842 1.909097 0 -0.9999523 -0.09090924 + + + + + + + + + + -4.30291e-6 -0.9667098 -0.2558753 -1 0 0 -1 0 0 -1 0 0 -0.1398547 0.9830996 -0.1181344 -1 0 0 -1 0 0 -1 0 0 -0.8847946 0.4504685 0.1192334 1 0 0 0 -0.9967921 0.08003413 1 0 0 1 0 0 0.04218304 0.9969479 -0.06569314 0 0.9997035 -0.02434897 0 0.9978359 -0.06575125 0.8847942 0.4504692 0.1192332 0.05835139 0.9968625 -0.05348128 1.35947e-7 0.9999688 0.007907867 0 -0.9997035 -0.02434885 0 -0.9990804 -0.04287761 0 -0.997836 -0.06575167 0.05124425 -0.9939407 -0.09724199 0 -0.9889047 -0.1485516 0 -0.9667094 -0.2558765 -1.0864e-5 -0.7751055 -0.631832 0 0.7750799 -0.6318633 1 0 0 -1 0 0 0 -0.9667096 -0.255876 0 -0.9997035 0.02434897 0.005943298 -0.9996091 0.02732098 0 -0.9999688 -0.007907986 -0.1445966 -0.9847888 -0.09634792 1 0 0 0 -0.997836 0.06575167 0 -0.7750795 -0.6318638 -4.39872e-6 -0.9667112 -0.2558697 0 -0.9990804 -0.04287761 0 -0.9999688 -0.007907867 0 -0.9952483 -0.0973699 0 -0.9889047 -0.1485516 1 0 0 1.08645e-5 -0.7750799 0.6318633 0.1398526 0.9830999 -0.1181349 -0.5337414 0.8456214 0.006687343 -1 0 0 0 -0.9997035 -0.02434885 -0.04218304 -0.9969479 -0.06569314 -1 0 0 1 0 0 0 -0.9990803 0.04287749 0 -0.9978361 0.06575137 -0.8358052 0.5472648 0.04394102 1 0 0 0 -0.9952481 0.09737133 -0.6394789 0.7685807 0.01871967 0.1828543 0.9784682 0.09572935 0 0.9996098 -0.02793151 -0.1828528 0.9784686 0.09572935 0 -0.9999688 -0.007907986 -0.9350987 -0.3395701 0.1014028 -0.5683284 -0.8201624 0.06585264 -0.05834925 -0.9968626 0.05348128 0.1316473 0.9901199 -0.04828459 0 0.9990803 -0.04287749 -1 0 0 -0.08664882 0.9891232 -0.1188584 0.3858988 -0.9159517 0.1100657 0.9343671 0.3444508 -0.09116965 0.1877753 0.9808015 -0.05261939 0.5192443 -0.8545992 -0.006758213 -1.46871e-7 -0.9999687 -0.007907807 0 -0.9997035 -0.02434897 -1 0 0 -0.852481 0.5002485 0.1517487 -0.4765982 -0.8788607 0.02140551 -0.1330115 -0.990669 -0.02971053 0.1592161 -0.09676676 -0.9824899 -0.876047 0.4252853 0.2273194 -0.3650873 0.9264903 0.09125143 0.2079594 -0.1908252 -0.9593428 -0.9524879 0.02985358 0.3031099 1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 0 0.9569405 -0.2902842 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 0 -0.9990803 0.04287743 0 -0.9997035 0.02434879 0 0.9988647 0.04763752 0 -0.9951848 -0.09801697 0 -0.9569403 -0.2902848 0 -0.8819214 -0.4713966 0.02844125 -0.5553455 -0.8311333 -1 0 0 -0.4878984 -0.8701003 0.06986182 0 -0.9898744 0.141946 -1 0 0 0 0.8819214 -0.4713966 0 0.9944189 -0.105504 -0.2413209 -0.970371 0.01201611 1 0 0 0 0.6343934 -0.7730104 0 -0.7730104 -0.6343933 0 -0.8819214 -0.4713966 0 -0.9997035 0.02434879 -1 0 0 0 -0.9951847 -0.09801703 0 -0.9569403 -0.2902848 1 0 0 1 0 0 -1 0 0 -0.09759616 0.9904338 -0.09754902 0.234192 0.9417178 0.2414987 -1 0 0 0 0.9988647 0.04763752 1 0 0 1 0 0 0.03748321 -0.7724673 0.6339473 0.08122903 -0.4698392 0.8790068 -0.6640971 0.3524382 -0.6593651 1 0 0 0 0.3826835 -0.9238796 0.1401528 0.9801536 0.1401996 1 0 0 0 0.8819215 -0.4713963 -0.6212959 -0.7748823 0.1163991 0 -0.9951847 0.09801691 -0.1415497 -0.9899231 -0.004003465 0.808264 0.2253317 -0.543999 1 0 0 0.2533497 -0.8531485 0.4560171 0 -0.8314697 0.5555701 0.5068296 -0.3298907 -0.796427 0.02844148 -0.3825287 0.9235058 -0.1592164 0.7631499 -0.6263006 -0.2865136 0.1869115 0.939667 -0.3784648 0.8645817 -0.3305493 0.3432393 -0.2948858 -0.8917562 -0.5082683 0.4059661 0.7595096 0.1207407 -0.991887 0.03977322 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 26 0 1 0 6 1 14 1 12 1 12 2 8 2 6 2 14 3 6 3 4 3 19 4 16 4 27 4 16 5 14 5 4 5 12 6 10 6 8 6 27 7 21 7 19 7 27 8 16 8 1 8 15 9 3 9 5 9 22 10 23 10 26 10 20 11 26 11 18 11 15 12 17 12 3 12 23 13 24 13 26 13 29 14 30 14 31 14 22 15 28 15 23 15 17 16 26 16 0 16 24 17 28 17 31 17 0 18 1 18 2 18 3 19 2 19 4 19 5 20 4 20 6 20 7 21 6 21 8 21 7 22 8 22 10 22 10 23 12 23 11 23 12 24 14 24 13 24 14 25 16 25 15 25 17 26 16 26 19 26 22 27 26 27 20 27 16 28 4 28 2 28 26 29 27 29 1 29 31 30 28 30 29 30 67 31 30 31 29 31 33 32 35 32 34 32 35 33 37 33 36 33 5 34 13 34 15 34 24 35 25 35 26 35 15 36 16 36 17 36 13 37 14 37 15 37 7 38 5 38 6 38 3 39 0 39 2 39 9 40 10 40 11 40 11 41 12 41 13 41 7 42 9 42 11 42 18 43 17 43 19 43 18 44 26 44 17 44 77 45 32 45 34 45 33 46 37 46 35 46 5 47 3 47 4 47 9 48 7 48 10 48 20 49 28 49 22 49 11 50 13 50 7 50 31 51 30 51 25 51 18 52 33 52 32 52 18 53 37 53 33 53 5 54 7 54 13 54 21 55 27 55 26 55 77 56 34 56 36 56 17 57 0 57 3 57 29 58 28 58 67 58 1 59 16 59 2 59 32 60 33 60 34 60 36 61 37 61 77 61 28 62 20 62 77 62 28 63 24 63 23 63 21 64 30 64 67 64 31 65 25 65 24 65 20 66 18 66 32 66 25 67 21 67 26 67 21 68 25 68 30 68 21 69 67 69 19 69 20 70 32 70 77 70 67 71 37 71 19 71 19 72 37 72 18 72 34 73 35 73 36 73 38 74 39 74 64 74 44 75 50 75 52 75 50 76 44 76 46 76 52 77 42 77 44 77 57 78 65 78 54 78 54 79 42 79 52 79 50 80 46 80 48 80 65 81 57 81 59 81 65 82 39 82 54 82 53 83 43 83 41 83 60 84 64 84 61 84 58 85 56 85 64 85 53 86 41 86 55 86 61 87 64 87 62 87 68 88 70 88 69 88 60 89 61 89 66 89 55 90 38 90 64 90 62 91 70 91 66 91 38 92 40 92 39 92 41 93 42 93 40 93 43 94 44 94 42 94 45 95 46 95 44 95 45 96 48 96 46 96 48 97 49 97 50 97 50 98 51 98 52 98 52 99 53 99 54 99 55 100 57 100 54 100 60 101 58 101 64 101 54 102 40 102 42 102 64 103 39 103 65 103 70 104 68 104 66 104 67 105 68 105 69 105 72 106 73 106 74 106 74 107 75 107 76 107 43 108 53 108 51 108 62 109 64 109 63 109 53 110 55 110 54 110 51 111 53 111 52 111 45 112 44 112 43 112 41 113 40 113 38 113 47 114 49 114 48 114 49 115 51 115 50 115 45 116 49 116 47 116 56 117 57 117 55 117 56 118 55 118 64 118 77 119 73 119 71 119 72 120 74 120 76 120 43 121 42 121 41 121 47 122 48 122 45 122 58 123 60 123 66 123 49 124 45 124 51 124 70 125 63 125 69 125 56 126 71 126 72 126 56 127 72 127 76 127 43 128 51 128 45 128 59 129 64 129 65 129 77 130 75 130 73 130 55 131 41 131 38 131 68 132 67 132 66 132 39 133 40 133 54 133 71 134 73 134 72 134 75 135 77 135 76 135 66 136 77 136 58 136 66 137 61 137 62 137 59 138 67 138 69 138 70 139 62 139 63 139 58 140 71 140 56 140 63 141 64 141 59 141 59 142 69 142 63 142 59 143 57 143 67 143 58 144 77 144 71 144 67 145 57 145 76 145 57 146 56 146 76 146 73 147 75 147 74 147

+
+
+
+ + + + 1 0.4744526 13.27272 0.4452555 0.4744526 13.27273 1 0.465336 14.42553 0.4452555 0.465336 14.42553 1 0.438337 15.53404 0.4452555 0.438337 15.53404 1 0.3944929 16.55564 0.4452555 0.3944929 16.55564 1 0.3354886 17.45108 0.4452555 0.3354886 17.45108 1 0.2635917 18.18596 0.4452555 0.2635917 18.18596 1 0.1815651 18.73201 0.4452555 0.1815651 18.73201 1 0.09256112 19.06827 0.4452555 0.09256112 19.06828 1 0 19.18182 0.4452555 0 19.18182 1 -0.092561 19.06827 0.4452555 -0.092561 19.06828 1 -0.1815651 18.73201 0.4452555 -0.1815651 18.73201 1 -0.2635917 18.18596 0.4452555 -0.2635917 18.18596 1 -0.3354886 17.45108 0.4452555 -0.3354886 17.45108 1 -0.3944929 16.55564 0.4452555 -0.3944929 16.55564 1 -0.438337 15.53404 0.4452555 -0.438337 15.53404 1 -0.4653361 14.42553 0.4452555 -0.4653361 14.42553 1 -0.4744526 13.27272 0.4452555 -0.4744526 13.27272 1 -0.465336 12.11992 0.4452555 -0.465336 12.11992 1 -0.4383369 11.01141 0.4452555 4.58131e-7 7.363636 1 0.09256154 7.477179 1 0.1815656 7.81344 1 0.2635922 8.359501 1 0.335489 9.094374 1 0.3944932 9.989818 1 0.4383373 11.01142 0.4452555 0.4383373 11.01142 1 0.4653362 12.11993 0.4452555 0.4653362 12.11993 1 1 0.9090906 -1 1 0.9090908 1 0.9807853 1.104181 -1 0.9807853 1.104181 1 0.9238795 1.291774 -1 0.9238795 1.291774 1 0.8314696 1.464661 -0.9999999 0.8314696 1.464661 1 0.7071068 1.616197 1 0.5555702 1.74056 1 0.3826834 1.83297 1 0.1950902 1.889876 1 0 1.909091 1 -0.1950902 1.889876 1 -0.3826833 1.83297 1 -0.5555702 1.74056 -0.9999999 -0.5555702 1.740561 1 -0.7071068 1.616197 -0.9999998 -0.7071068 1.616198 1 -0.8314697 1.464661 -1 -0.8314697 1.464661 1 -0.9238796 1.291774 -1 -0.9238796 1.291774 1 -0.9807853 1.104181 -1 -0.9807853 1.104181 1 -1 0.9090903 -1 -1 0.9090904 -0.4578285 -0.8939037 1.909092 -0.3081837 -0.9558849 -0.09090924 0.002650022 -1.00842 1.909097 0 -0.9999523 -0.09090924 + + + + + + + + + + -4.30291e-6 -0.9667098 -0.2558753 -1 0 0 -1 0 0 -1 0 0 -0.1398547 0.9830996 -0.1181344 -1 0 0 -1 0 0 -1 0 0 -0.8847946 0.4504685 0.1192334 1 0 0 0 -0.9967921 0.08003413 1 0 0 1 0 0 0.04218304 0.9969479 -0.06569314 0 0.9997035 -0.02434897 0 0.9978359 -0.06575125 0.8847942 0.4504692 0.1192332 0.05835139 0.9968625 -0.05348128 1.35947e-7 0.9999688 0.007907867 0 -0.9997035 -0.02434885 0 -0.9990804 -0.04287761 0 -0.997836 -0.06575167 0.05124425 -0.9939407 -0.09724199 0 -0.9889047 -0.1485516 0 -0.9667094 -0.2558765 -1.0864e-5 -0.7751055 -0.631832 0 0.7750799 -0.6318633 1 0 0 -1 0 0 0 -0.9667096 -0.255876 0 -0.9997035 0.02434897 0.005943298 -0.9996091 0.02732098 0 -0.9999688 -0.007907986 -0.1445966 -0.9847888 -0.09634792 1 0 0 0 -0.997836 0.06575167 0 -0.7750795 -0.6318638 -4.39872e-6 -0.9667112 -0.2558697 0 -0.9990804 -0.04287761 0 -0.9999688 -0.007907867 0 -0.9952483 -0.0973699 0 -0.9889047 -0.1485516 1 0 0 1.08645e-5 -0.7750799 0.6318633 0.1398526 0.9830999 -0.1181349 -0.5337414 0.8456214 0.006687343 -1 0 0 0 -0.9997035 -0.02434885 -0.04218304 -0.9969479 -0.06569314 -1 0 0 1 0 0 0 -0.9990803 0.04287749 0 -0.9978361 0.06575137 -0.8358052 0.5472648 0.04394102 1 0 0 0 -0.9952481 0.09737133 -0.6394789 0.7685807 0.01871967 0.1828543 0.9784682 0.09572935 0 0.9996098 -0.02793151 -0.1828528 0.9784686 0.09572935 0 -0.9999688 -0.007907986 -0.9350987 -0.3395701 0.1014028 -0.5683284 -0.8201624 0.06585264 -0.05834925 -0.9968626 0.05348128 0.1316473 0.9901199 -0.04828459 0 0.9990803 -0.04287749 -1 0 0 -0.08664882 0.9891232 -0.1188584 0.3858988 -0.9159517 0.1100657 0.9343671 0.3444508 -0.09116965 0.1877753 0.9808015 -0.05261939 0.5192443 -0.8545992 -0.006758213 -1.46871e-7 -0.9999687 -0.007907807 0 -0.9997035 -0.02434897 -1 0 0 -0.852481 0.5002485 0.1517487 -0.4765982 -0.8788607 0.02140551 -0.1330115 -0.990669 -0.02971053 0.1592161 -0.09676676 -0.9824899 -0.876047 0.4252853 0.2273194 -0.3650873 0.9264903 0.09125143 0.2079594 -0.1908252 -0.9593428 -0.9524879 0.02985358 0.3031099 1 0 0 -1 0 0 -1 0 0 1 0 0 -1 0 0 0 0.9569405 -0.2902842 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 0 -0.9990803 0.04287743 0 -0.9997035 0.02434879 0 0.9988647 0.04763752 0 -0.9951848 -0.09801697 0 -0.9569403 -0.2902848 0 -0.8819214 -0.4713966 0.02844125 -0.5553455 -0.8311333 -1 0 0 -0.4878984 -0.8701003 0.06986182 0 -0.9898744 0.141946 -1 0 0 0 0.8819214 -0.4713966 0 0.9944189 -0.105504 -0.2413209 -0.970371 0.01201611 1 0 0 0 0.6343934 -0.7730104 0 -0.7730104 -0.6343933 0 -0.8819214 -0.4713966 0 -0.9997035 0.02434879 -1 0 0 0 -0.9951847 -0.09801703 0 -0.9569403 -0.2902848 1 0 0 1 0 0 -1 0 0 -0.09759616 0.9904338 -0.09754902 0.234192 0.9417178 0.2414987 -1 0 0 0 0.9988647 0.04763752 1 0 0 1 0 0 0.03748321 -0.7724673 0.6339473 0.08122903 -0.4698392 0.8790068 -0.6640971 0.3524382 -0.6593651 1 0 0 0 0.3826835 -0.9238796 0.1401528 0.9801536 0.1401996 1 0 0 0 0.8819215 -0.4713963 -0.6212959 -0.7748823 0.1163991 0 -0.9951847 0.09801691 -0.1415497 -0.9899231 -0.004003465 0.808264 0.2253317 -0.543999 1 0 0 0.2533497 -0.8531485 0.4560171 0 -0.8314697 0.5555701 0.5068296 -0.3298907 -0.796427 0.02844148 -0.3825287 0.9235058 -0.1592164 0.7631499 -0.6263006 -0.2865136 0.1869115 0.939667 -0.3784648 0.8645817 -0.3305493 0.3432393 -0.2948858 -0.8917562 -0.5082683 0.4059661 0.7595096 0.1207407 -0.991887 0.03977322 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 26 0 1 0 6 1 14 1 12 1 12 2 8 2 6 2 14 3 6 3 4 3 19 4 16 4 27 4 16 5 14 5 4 5 12 6 10 6 8 6 27 7 21 7 19 7 27 8 16 8 1 8 15 9 3 9 5 9 22 10 23 10 26 10 20 11 26 11 18 11 15 12 17 12 3 12 23 13 24 13 26 13 29 14 30 14 31 14 22 15 28 15 23 15 17 16 26 16 0 16 24 17 28 17 31 17 0 18 1 18 2 18 3 19 2 19 4 19 5 20 4 20 6 20 7 21 6 21 8 21 7 22 8 22 10 22 10 23 12 23 11 23 12 24 14 24 13 24 14 25 16 25 15 25 17 26 16 26 19 26 22 27 26 27 20 27 16 28 4 28 2 28 26 29 27 29 1 29 31 30 28 30 29 30 67 31 30 31 29 31 33 32 35 32 34 32 35 33 37 33 36 33 5 34 13 34 15 34 24 35 25 35 26 35 15 36 16 36 17 36 13 37 14 37 15 37 7 38 5 38 6 38 3 39 0 39 2 39 9 40 10 40 11 40 11 41 12 41 13 41 7 42 9 42 11 42 18 43 17 43 19 43 18 44 26 44 17 44 77 45 32 45 34 45 33 46 37 46 35 46 5 47 3 47 4 47 9 48 7 48 10 48 20 49 28 49 22 49 11 50 13 50 7 50 31 51 30 51 25 51 18 52 33 52 32 52 18 53 37 53 33 53 5 54 7 54 13 54 21 55 27 55 26 55 77 56 34 56 36 56 17 57 0 57 3 57 29 58 28 58 67 58 1 59 16 59 2 59 32 60 33 60 34 60 36 61 37 61 77 61 28 62 20 62 77 62 28 63 24 63 23 63 21 64 30 64 67 64 31 65 25 65 24 65 20 66 18 66 32 66 25 67 21 67 26 67 21 68 25 68 30 68 21 69 67 69 19 69 20 70 32 70 77 70 67 71 37 71 19 71 19 72 37 72 18 72 34 73 35 73 36 73 38 74 39 74 64 74 44 75 50 75 52 75 50 76 44 76 46 76 52 77 42 77 44 77 57 78 65 78 54 78 54 79 42 79 52 79 50 80 46 80 48 80 65 81 57 81 59 81 65 82 39 82 54 82 53 83 43 83 41 83 60 84 64 84 61 84 58 85 56 85 64 85 53 86 41 86 55 86 61 87 64 87 62 87 68 88 70 88 69 88 60 89 61 89 66 89 55 90 38 90 64 90 62 91 70 91 66 91 38 92 40 92 39 92 41 93 42 93 40 93 43 94 44 94 42 94 45 95 46 95 44 95 45 96 48 96 46 96 48 97 49 97 50 97 50 98 51 98 52 98 52 99 53 99 54 99 55 100 57 100 54 100 60 101 58 101 64 101 54 102 40 102 42 102 64 103 39 103 65 103 70 104 68 104 66 104 67 105 68 105 69 105 72 106 73 106 74 106 74 107 75 107 76 107 43 108 53 108 51 108 62 109 64 109 63 109 53 110 55 110 54 110 51 111 53 111 52 111 45 112 44 112 43 112 41 113 40 113 38 113 47 114 49 114 48 114 49 115 51 115 50 115 45 116 49 116 47 116 56 117 57 117 55 117 56 118 55 118 64 118 77 119 73 119 71 119 72 120 74 120 76 120 43 121 42 121 41 121 47 122 48 122 45 122 58 123 60 123 66 123 49 124 45 124 51 124 70 125 63 125 69 125 56 126 71 126 72 126 56 127 72 127 76 127 43 128 51 128 45 128 59 129 64 129 65 129 77 130 75 130 73 130 55 131 41 131 38 131 68 132 67 132 66 132 39 133 40 133 54 133 71 134 73 134 72 134 75 135 77 135 76 135 66 136 77 136 58 136 66 137 61 137 62 137 59 138 67 138 69 138 70 139 62 139 63 139 58 140 71 140 56 140 63 141 64 141 59 141 59 142 69 142 63 142 59 143 57 143 67 143 58 144 77 144 71 144 67 145 57 145 76 145 57 146 56 146 76 146 73 147 75 147 74 147

+
+
+
+
+ + + + + Cylinder_001-mesh_morph_Cylinder_002 Cylinder_001-mesh_morph_Cylinder_001 + + + + + + + + 0 0 + + + + + + + + + + + + + + + + + 0.0685 0 0 0 0 0.0685 0 0 0 0 0.0055 4.65661e-10 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/meshes/stand.dae b/meshes/stand.dae new file mode 100644 index 0000000..8188165 --- /dev/null +++ b/meshes/stand.dae @@ -0,0 +1,100 @@ + + + + + Blender User + Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b + + 2015-09-11T13:28:18 + 2015-09-11T13:28:18 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.3617391 0.3617391 0.3617391 1 + + + 0.04347828 0.04347828 0.04347828 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + -1.029193 -3.211652 0.01340484 -1.049492 -1.978712 0.01340532 -1.009731 -3.211639 1.934296 -1.039565 -1.957522 1.934432 0.007422864 3.073923 0.01340341 0.007422924 3.073923 1.934565 -1.312955 -1.33704 0.01340508 -1.290127 -1.306191 1.934325 -1.432244 -0.5491396 1.934346 -1.557081 -0.4490664 0.01340472 -1.576782 0.4654509 1.934516 -1.530406 0.5052257 0.0134043 -1.42693 0.5900794 1.934393 -1.256991 1.580693 0.01340448 -1.275665 1.410018 1.93436 -0.7085953 2.50742 0.01340395 -0.9118301 2.255287 1.934535 -0.4995788 2.634755 1.934362 -0.2895518 2.781127 0.01340341 -0.3016678 2.71808 1.934299 -1 -3.211677 3.934154 -1.019723 -1.914941 3.934154 0.00811243 2.761013 1.934153 0.00811243 2.761013 3.934153 -1.356949 -1.002933 3.934155 -1.438625 0.3433758 3.934154 -1.260525 1.377793 3.934154 -0.9249734 2.140849 1.934146 -0.8859624 2.198979 3.934156 -0.3779678 2.678211 3.934152 -1.56095 -0.4548287 1.934566 -0.2531765 3.021127 1.934565 -0.2531765 3.021127 0.01340341 0.02320307 -3.211677 3.934154 0.02320289 -3.211625 0.01340508 1.029193 -3.211652 0.01340484 1.049492 -1.978712 0.01340532 1.009731 -3.211639 1.934296 1.039565 -1.957521 1.934431 -0.007422864 3.073923 0.01340341 -0.007422924 3.073923 1.934565 1.312956 -1.337036 0.01340508 1.290126 -1.306191 1.934324 1.455687 -0.5348288 0.01340484 1.432244 -0.5491396 1.934346 1.576783 -0.4348014 0.0134046 1.576782 0.4654508 1.934516 1.530406 0.5052257 0.01340436 1.42693 0.5900794 1.934393 1.256991 1.580693 0.01340448 1.275665 1.410018 1.93436 0.7085953 2.507423 0.01340395 0.9118301 2.255287 1.934535 0.4995712 2.634755 1.934361 0.2895518 2.781127 0.01340341 0.3016678 2.71808 1.934298 1 -3.211677 3.934154 1.019723 -1.914941 3.934154 -0.00811243 2.761013 1.934153 -0.00811243 2.761013 3.934153 1.356949 -1.002933 3.934155 1.438625 0.3433758 3.934154 1.260525 1.377793 3.934154 0.9249753 2.140853 1.934146 0.8859567 2.198975 3.934156 0.3779678 2.678211 3.934152 1.56095 -0.4548287 1.934566 0.2531765 3.021127 1.934565 0.2531765 3.021127 0.01340341 -0.02320307 -3.211677 3.934154 -0.02320289 -3.211625 0.01340508 + + + + + + + + + + -0.9998501 -0.01646125 0.005348563 -0.9331902 -0.3589877 0.01685523 -0.9827268 -0.1844822 0.0146414 -0.9833843 0.1814176 0.006558716 -0.9182102 0.3952265 0.02618902 -0.6770306 0.7355332 0.02491015 -0.3878777 0.9212918 0.02779197 -0.9996659 -0.02378189 0.01012879 -0.9250237 -0.3798036 0.008969604 -0.9630753 -0.2647732 0.0487942 2.26555e-7 -2.6495e-7 -1 0 -3.8529e-7 -1 1.43316e-6 -1.62063e-7 1 -0.968344 0.2461816 0.0412867 -0.8603553 0.5091199 -0.02419841 -0.5468501 0.8372209 0.004004776 -0.9996628 -0.02378189 0.01042526 -0.9377226 -0.3467346 0.02124619 -0.9978813 -0.06053757 0.02383387 -0.9854484 0.1696685 0.01019495 -0.9098101 0.414986 0.005684614 -0.6859837 0.7271553 0.02591443 -0.2096982 0.9777661 0 -0.9998725 -0.01520782 0.004864811 -0.9331893 -0.3589874 0.01690346 -0.1985601 0.9800887 0 -0.9828206 -0.1844993 -0.004862308 -0.9999752 0.004664361 -0.005272448 -0.9832694 0.1813968 0.01662808 -0.901487 0.4325861 0.01379591 -0.7576953 0.6525949 -0.004188477 -0.1372569 0.9904292 0.0145083 -0.3880316 0.9216391 0.003569185 0.003970801 -0.003857076 0.9999846 0.01012045 -0.004563212 0.9999384 -0.6394315 0.7688481 4.82258e-4 0 -1 -1.91941e-5 -0.9874387 0.1580023 0 2.66313e-4 -0.001314461 0.9999991 0.001768767 8.43173e-5 0.9999985 -1.14958e-5 -1 -1.32565e-5 2.53734e-5 -1 6.56944e-6 -0.5910636 -0.806617 -0.003609657 6.04905e-4 -9.74397e-4 0.9999994 -0.9998499 -0.01720154 -0.002065181 -0.9887076 0.1498523 -0.001317799 8.60097e-4 -4.51357e-5 0.9999997 -0.9993325 0.02793335 -0.02354568 -0.1985601 0.9800887 0 -5.40638e-6 1.36909e-5 1 7.301e-6 -6.52384e-6 1 0 2.43918e-7 1 -1.04422e-6 8.22104e-7 1 2.03308e-6 -2.93932e-7 1 4.28559e-6 -4.34676e-6 -1 0 -3.88783e-7 -1 0 -3.75982e-7 -1 0 0 -1 -1.40737e-6 4.73835e-7 -1 -1.49494e-6 3.1181e-7 -1 -3.38693e-6 3.30986e-7 -1 0 0 1 0.9998502 -0.01646125 0.005348324 0.9331905 -0.3589866 0.01685541 0.9827266 -0.1844834 0.01464205 0.9833843 0.1814176 0.006558716 0.9182102 0.3952265 0.02618902 0.6770237 0.7355393 0.02491313 0.3878905 0.9212865 0.02779173 0.9996659 -0.02378237 0.01012885 0.925024 -0.3798028 0.008969664 0.9844814 -0.1751616 0.01070964 -1.24501e-6 -3.73506e-7 -1 -2.26555e-7 -2.6495e-7 -1 -1.39437e-7 -4.52933e-7 -1 -1.43316e-6 -1.62063e-7 1 0.968344 0.2461816 0.0412867 0.8603563 0.5091184 -0.02419775 0.5468447 0.8372244 0.004007816 0.9996628 -0.02378231 0.01042544 0.9377226 -0.3467346 0.02124571 0.9978813 -0.06053757 0.02383387 0.9854484 0.1696685 0.01019495 0.909807 0.4149929 0.005689382 0.6859908 0.7271488 0.02591234 0.2096982 0.9777661 0 0.9998725 -0.01520782 0.004864752 0.9331898 -0.3589863 0.0169034 0.1985601 0.9800887 0 0.9828204 -0.1845005 -0.004862606 0.9999752 0.004664361 -0.005272448 0.9832694 0.1813968 0.01662808 0.9014889 0.4325824 0.01379585 0.7576857 0.6526063 -0.00418365 0.137257 0.9904292 0.0145083 0.3880443 0.9216337 0.003568589 -0.003973841 -0.003857612 0.9999846 -0.01012146 -0.004563689 0.9999383 0.6394324 0.7688472 4.82345e-4 0 -1 -1.91941e-5 0.9874387 0.1580023 0 -2.66313e-4 -0.001314461 0.9999991 0.6368463 -0.7709858 -0.002788662 -0.001768767 8.43168e-5 0.9999984 1.14958e-5 -1 -1.32565e-5 -2.53734e-5 -1 6.56944e-6 0.5910614 -0.8066257 0.001204013 -6.03554e-4 -9.75755e-4 0.9999994 0.9998196 -0.01720023 0.008060634 0.9887076 0.1498523 -0.001317799 -8.60098e-4 -4.51357e-5 0.9999997 0.9985191 0.04926228 -0.02308434 0.1985601 0.9800887 0 5.40633e-6 1.36907e-5 1 -7.30117e-6 -6.524e-6 1 0 2.43918e-7 1 1.04422e-6 8.22104e-7 1 -2.03308e-6 -2.93932e-7 1 -4.28559e-6 -4.34676e-6 -1 1.74027e-7 -3.25844e-7 -1 0 -3.76471e-7 -1 0 0 -1 1.40445e-6 4.7136e-7 -1 1.53716e-6 3.45842e-7 -1 3.38693e-6 3.30986e-7 -1 0 0 1 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

3 0 1 0 0 0 3 1 7 1 6 1 6 2 7 2 8 2 12 3 14 3 13 3 14 4 16 4 13 4 16 5 17 5 15 5 17 6 19 6 18 6 2 7 3 7 0 7 1 8 3 8 6 8 9 9 6 9 8 9 34 10 0 10 4 10 11 11 4 11 9 11 21 12 20 12 23 12 11 13 12 13 13 13 13 14 16 14 15 14 15 15 17 15 18 15 21 16 3 16 2 16 21 17 24 17 7 17 24 18 25 18 8 18 25 19 26 19 14 19 26 20 28 20 27 20 28 21 29 21 17 21 29 22 23 22 22 22 20 23 21 23 2 23 3 24 21 24 7 24 32 25 31 25 5 25 8 26 7 26 24 26 8 27 25 27 12 27 12 28 25 28 14 28 14 29 26 29 27 29 27 30 28 30 17 30 19 31 29 31 22 31 17 32 29 32 19 32 17 33 16 33 27 33 27 34 16 34 14 34 11 35 10 35 12 35 20 36 2 36 33 36 19 37 31 37 32 37 5 38 31 38 22 38 10 39 30 39 8 39 34 40 33 40 2 40 2 41 0 41 34 41 8 42 30 42 9 42 22 43 31 43 19 43 10 44 9 44 30 44 18 45 19 45 32 45 10 46 8 46 12 46 9 47 10 47 11 47 4 48 32 48 5 48 23 49 29 49 28 49 23 50 28 50 26 50 23 51 26 51 25 51 25 52 24 52 23 52 21 53 23 53 24 53 18 54 4 54 13 54 4 55 6 55 9 55 4 56 1 56 6 56 4 57 18 57 32 57 13 58 4 58 11 58 18 59 13 59 15 59 0 60 1 60 4 60 20 61 33 61 23 61 38 62 35 62 36 62 38 63 41 63 42 63 41 64 44 64 42 64 48 65 49 65 50 65 50 66 49 66 52 66 52 67 51 67 53 67 53 68 54 68 55 68 37 69 35 69 38 69 36 70 41 70 38 70 43 71 44 71 41 71 43 72 47 72 45 72 70 73 39 73 35 73 47 74 43 74 39 74 57 75 59 75 56 75 47 76 49 76 48 76 49 77 51 77 52 77 51 78 54 78 53 78 57 79 37 79 38 79 57 80 42 80 60 80 60 81 44 81 61 81 61 82 50 82 62 82 62 83 63 83 64 83 64 84 53 84 65 84 65 85 58 85 59 85 56 86 37 86 57 86 38 87 42 87 57 87 68 88 40 88 67 88 44 89 60 89 42 89 44 90 48 90 61 90 48 91 50 91 61 91 50 92 63 92 62 92 63 93 53 93 64 93 55 94 58 94 65 94 53 95 55 95 65 95 53 96 63 96 52 96 63 97 50 97 52 97 47 98 48 98 46 98 56 99 69 99 37 99 55 100 68 100 67 100 40 101 58 101 67 101 66 102 43 102 45 102 46 103 44 103 66 103 70 104 37 104 69 104 37 105 70 105 35 105 44 106 43 106 66 106 58 107 55 107 67 107 46 108 66 108 45 108 54 109 68 109 55 109 46 110 48 110 44 110 45 111 47 111 46 111 39 112 40 112 68 112 59 113 64 113 65 113 59 114 62 114 64 114 59 115 61 115 62 115 61 116 59 116 60 116 57 117 60 117 59 117 54 118 49 118 39 118 39 119 43 119 41 119 39 120 41 120 36 120 39 121 68 121 54 121 49 122 47 122 39 122 54 123 51 123 49 123 35 124 39 124 36 124 56 125 59 125 69 125

+
+
+
+
+ + + + + 0.0475 0 0 0 0 0.025 0 0 0 0 0.015 -3.72529e-9 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/meshes/tilt_head.dae b/meshes/tilt_head.dae new file mode 100644 index 0000000..b8603b5 --- /dev/null +++ b/meshes/tilt_head.dae @@ -0,0 +1,106 @@ + + + + + Blender User + Blender 2.71.0 commit date:2014-06-12, commit time:18:39, hash:169c95b + + 2015-09-11T10:37:44 + 2015-09-11T10:37:44 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.5652174 0.5652174 0.5652174 1 + + + 0.1739131 0.1739131 0.1739131 1 + + + 50 + + + 1 + + + + + + 1 + + + + 1 + + + + + + + + + + + + 0 0.9000002 1.339083 0 0.7513147 1.424958 0.3444151 0.8314918 1.339083 0.6363961 0.6363964 1.339083 0.7483227 0.5000134 1.339083 0.6246953 0.4174082 1.424958 0.8827068 0.1755815 1.339083 0.8827068 -0.1755809 1.339083 0.7368783 -0.146574 1.424958 0.7483227 -0.500013 1.339083 0.6363961 -0.6363959 1.339083 0.344415 -0.8314915 1.339083 0.2875155 -0.6941241 1.424958 -2.87902e-7 -0.8999999 1.339083 -0.1755816 -0.8827065 1.339083 -0.1465744 -0.7368782 1.424958 -0.5000137 -0.7483222 1.339083 -0.748323 -0.5000125 1.339083 -0.8827069 -0.1755803 1.339083 -0.7368785 -0.1465734 1.424958 -0.8827066 0.1755824 1.339083 -0.7483221 0.5000144 1.339083 -0.6246948 0.417409 1.424958 -0.6363953 0.6363971 1.339083 -0.3444139 0.8314923 1.339083 -1 0.9999999 -1.666667 -1 1 1.333333 1 1 1.333333 1 0.9999999 -1.666667 -1 -0.8038242 -1.422585 -1 -0.9999998 1.333333 1 -0.9999998 1.333333 1 -0.8038242 -1.422585 1 -1 -1 -1 -1 -1 -1 -0.490277 -1.630645 1 -0.490277 -1.630645 + + + + + + + + + + 0.3880131 0.3184342 0.8648962 0.468807 -0.1941862 0.8616912 -0.04919999 -0.4995341 0.8648961 -0.4688072 -0.1941858 0.8616911 -0.3880129 0.3184347 0.8648962 0.4688069 0.1941861 0.8616912 -0.4688068 0.1941867 0.8616913 0 0 1 0 -0.02416437 -0.9997079 0 -0.02416437 -0.9997079 0 1 0 0 -1 1.27724e-7 0 -0.5529113 -0.8332401 0.0989952 0.4976826 0.8616914 0.1629795 0.3049134 0.9383313 0.2302434 0.3445837 0.9100825 0.2672587 -0.2193336 0.9383312 0.2819147 -0.4219152 0.8616912 0.04284346 -0.4349983 0.8994114 0.09899514 -0.4976829 0.8616911 -0.1941865 -0.4688071 0.8616911 -0.2233065 -0.2233062 0.9488248 -0.2233065 -0.2233062 0.9488248 -0.09899479 0.4976825 0.8616914 -0.1629795 0.3049138 0.9383311 -0.2302429 0.344584 0.9100824 0.3775769 0.07510471 0.9229273 0.5074329 0 0.8616912 -0.3775768 0.07510507 0.9229274 -0.507433 5.17148e-7 0.8616912 0 0 1 0.2672588 -0.2193336 0.9383312 0 0 1 0 0 1 0 0 1 0.008684337 -0.007127046 0.9999368 0.006333112 -0.009478211 0.9999351 0.003825247 -0.0192309 0.9998078 0 -0.05739986 0.9983512 -0.002851665 -0.02895349 0.9995766 -0.005190491 -0.01253092 0.999908 -0.007648527 -0.007648527 0.9999415 -0.01253092 -0.005190432 0.999908 -0.04895949 0 0.9988008 -0.04896014 0 0.9988007 -0.01253145 0.00519067 0.999908 -0.008684694 0.007127344 0.9999369 -0.00633341 0.009478628 0.9999351 -0.003825366 0.01923173 0.9998078 0 0.05740225 0.9983512 0.003825426 0.01923167 0.9998077 0.00633341 0.009478628 0.9999351 0.008684694 0.007127344 0.9999368 0.01253145 0.00519067 0.999908 0.04896104 0 0.9988007 0.04895991 0 0.9988008 0.01253092 -0.005190491 0.999908 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 1 0 0 1 0 0 -1 0 0 0 -0.5529113 -0.8332401 -1 0 0 0 -0.9070287 -0.4210686 0 -0.9070287 -0.4210686 0 -1 1.27724e-7 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 +

5 0 4 0 3 0 7 1 8 1 9 1 15 2 14 2 13 2 19 3 18 3 17 3 21 4 22 4 23 4 4 5 5 5 6 5 22 6 21 6 20 6 1 7 22 7 5 7 28 8 35 8 25 8 35 9 28 9 36 9 26 10 27 10 28 10 31 11 30 11 33 11 29 12 35 12 36 12 0 13 1 13 2 13 1 14 5 14 2 14 5 15 3 15 2 15 9 16 8 16 10 16 12 17 11 17 10 17 12 18 15 18 13 18 11 19 12 19 13 19 14 20 15 20 16 20 15 21 19 21 17 21 16 22 15 22 17 22 1 23 0 23 24 23 22 24 1 24 24 24 23 25 22 25 24 25 5 26 8 26 6 26 8 27 7 27 6 27 19 28 22 28 20 28 18 29 19 29 20 29 5 30 22 30 15 30 8 31 12 31 10 31 15 32 12 32 8 32 5 33 15 33 8 33 22 34 19 34 15 34 9 35 10 35 31 35 11 36 31 36 10 36 13 37 31 37 11 37 31 38 13 38 30 38 13 39 14 39 30 39 16 40 30 40 14 40 17 41 30 41 16 41 18 42 30 42 17 42 20 43 30 43 18 43 30 44 20 44 26 44 20 45 21 45 26 45 23 46 26 46 21 46 24 47 26 47 23 47 0 48 26 48 24 48 26 49 0 49 27 49 0 50 2 50 27 50 3 51 27 51 2 51 4 52 27 52 3 52 6 53 27 53 4 53 7 54 27 54 6 54 27 55 7 55 31 55 7 56 9 56 31 56 35 57 29 57 34 57 34 58 30 58 26 58 27 59 31 59 33 59 33 60 32 60 36 60 25 61 26 61 28 61 28 62 27 62 33 62 33 63 36 63 28 63 26 64 25 64 35 64 32 65 29 65 36 65 34 66 26 66 35 66 32 67 33 67 34 67 29 68 32 68 34 68 34 69 33 69 30 69

+
+
+
+
+ + + + + 0.03 0 0 0 0 2.26494e-9 0.03 0 0 -0.03 2.26494e-9 4.44089e-16 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/msg/PTZ.msg b/msg/PTZ.msg new file mode 100644 index 0000000..10147dd --- /dev/null +++ b/msg/PTZ.msg @@ -0,0 +1,4 @@ +Header header +float32 pan +float32 tilt +int32 zoom \ No newline at end of file diff --git a/msg/PointInRectangle.msg b/msg/PointInRectangle.msg new file mode 100644 index 0000000..6499942 --- /dev/null +++ b/msg/PointInRectangle.msg @@ -0,0 +1,4 @@ +int32 x +int32 y +int32 image_width +int32 image_height \ No newline at end of file diff --git a/nodes/axis.py b/nodes/axis.py index 2d0eba5..79067eb 100755 --- a/nodes/axis.py +++ b/nodes/axis.py @@ -1,193 +1,633 @@ #!/usr/bin/env python -# -# Axis camera image driver. Based on: -# https://code.ros.org/svn/wg-ros-pkg/branches/trunk_cturtle/sandbox/axis_camera -# /axis.py -# -import threading -import urllib2 +""" +Axis camera video driver. Inspired by: +https://code.ros.org/svn/wg-ros-pkg/branches/trunk_cturtle/sandbox/axis_camera/axis.py -import rospy +Communication with the camera is done using the Axis VAPIX API described at +http://www.axis.com/global/en/support/developer-support/vapix + +.. note:: + + This is a major rewrite of the former ros-drivers/axis_camera node, so it contains a (deprecated) backwards + compatibility layer for the previous (non-released) API. +""" + +import math +import re + +import rospy from sensor_msgs.msg import CompressedImage, CameraInfo import camera_info_manager +import dynamic_reconfigure.server +from diagnostic_updater import Updater, DiagnosedPublisher, TimeStampStatusParam, FrequencyStatusParam, \ + FunctionDiagnosticTask, DiagnosticStatusWrapper -class StreamThread(threading.Thread): - def __init__(self, axis): - threading.Thread.__init__(self) - self.axis = axis - self.daemon = True - self.timeoutSeconds = 2.5 - - def run(self): - while(True): - self.stream() - - def stream(self): - while(True): - self.formURL() - self.authenticate() - if self.openURL(): - self.publishFramesContinuously() - rospy.sleep(2) # if stream stays intact we shouldn't get to this - - def formURL(self): - self.url = 'http://%s/mjpg/video.mjpg' % self.axis.hostname - self.url += "?fps=0&resolution=%dx%d" % (self.axis.width, - self.axis.height) - rospy.logdebug('opening ' + str(self.axis)) - - def authenticate(self): - '''only try to authenticate if user/pass configured. I have not - used this method (yet).''' - if self.axis.password != '' and self.axis.username != '': - # create a password manager - password_mgr = urllib2.HTTPPasswordMgrWithDefaultRealm() - - # Add the username and password, use default realm. - top_level_url = "http://" + self.axis.hostname - password_mgr.add_password(None, top_level_url, self.axis.username, - self.axis.password) - if self.axis.use_encrypted_password : - handler = urllib2.HTTPDigestAuthHandler(password_mgr) - else: - handler = urllib2.HTTPBasicAuthHandler(password_mgr) - - # create "opener" (OpenerDirector instance) - opener = urllib2.build_opener(handler) - - # ...and install it globally so it can be used with urlopen. - urllib2.install_opener(opener) - - def openURL(self): - '''Open connection to Axis camera using http''' - try: - self.fp = urllib2.urlopen(self.url, timeout=self.timeoutSeconds) - return(True) - except urllib2.URLError, e: - rospy.logwarn('Error opening URL %s' % (self.url) + - 'Possible timeout. Looping until camera appears') - return(False) - - def publishFramesContinuously(self): - '''Continuous loop to publish images''' - while(True): - try: - self.findBoundary() - self.getImage() - self.publishMsg() - self.publishCameraInfoMsg() - except: - rospy.loginfo('Timed out while trying to get message.') - break - - def findBoundary(self): - '''The string "--myboundary" is used to denote the start of an image in - Axis cameras''' - while(True): - boundary = self.fp.readline() - if boundary=='--myboundary\r\n': - break - - def getImage(self): - '''Get the image header and image itself''' - self.getHeader() - self.getImageData() - - def getHeader(self): - self.header = {} - while(True): - line = self.fp.readline() - if line == "\r\n": - break - line = line.strip() - parts = line.split(": ", 1) +from axis_camera.cfg import VideoStreamConfig +from axis_camera.srv import TakeSnapshot, TakeSnapshotResponse +from axis_camera.vapix import VAPIX +from axis_camera.video_streaming import ImageStreamingThread +from axis_camera.dynamic_reconfigure_tools import change_enum_items + +# BACKWARDS COMPATIBILITY LAYER +StreamThread = ImageStreamingThread # deprecated + + +class Axis(rospy.SubscribeListener): + """The ROS-VAPIX interface for video streaming.""" + + def __init__(self, hostname, username, password, width, height, frame_id, camera_info_url, use_encrypted_password, + camera_id=1, auto_wakeup_camera=True, compression=0, fps=24, use_color=True, + use_square_pixels=False): + """Create the ROS-VAPIX interface. + + :param hostname: Hostname of the camera (without http://, can be an IP address). + :type hostname: basestring + :param username: If login is needed, provide a username here. + :type username: :py:obj:`basestring` | None + :param password: If login is needed, provide a password here. + :type password: :py:obj:`basestring` | None + :param width: Width of the requested video stream in pixels (can be changed later). Must be one of the supported + resolutions. If `None`, the resolution will be chosen by height only. If also `height` is `None`, + then the default camera resolution will be used. + :type width: int|None + :param height: Height of the requested video stream in pixels (can be changed later). Must be one of the + supported resolutions. If `None`, the resolution will be chosen by width only. If also `width` is + `None`, then the default camera resolution will be used. + :type height: int|None + :param frame_id: The ROS TF frame assigned to the camera. + :type frame_id: basestring + :param camera_info_url: The URL pointing to the camera calaibration, if available. + :type camera_info_url: basestring + :param use_encrypted_password: Whether to use Plain HTTP Auth (False) or Digest HTTP Auth (True). + :type use_encrypted_password: bool + :param camera_id: ID (number) of the camera. Can be 1 to 4. + :type camera_id: int + :param auto_wakeup_camera: If True, there will be a wakeup trial after first unsuccessful network command. + :type auto_wakeup_camera: bool + :param compression: Compression of the image (0 - no compression, 100 - max compression). + :type compression: int + :param fps: The desired frames per second. + :type fps: int + :param use_color: If True, send a color stream, otherwise send only grayscale image. + :type use_color: bool + :param use_square_pixels: If True, the resolution will be stretched to match 1:1 pixels. + By default, the pixels have a ratio of 11:12. + :type use_square_pixels: bool + :raises: :py:exc:`ValueError` if the requested resolution (either the `resolution`, or `width`+`height` + is not supported. + """ + # True every time the video parameters have changed and the URL has to be altered (set from other threads). + self.video_params_changed = False + + self.__initializing = True + + self._hostname = hostname + self._camera_id = camera_id + + self.diagnostic_updater = Updater() + self.diagnostic_updater.setHardwareID(hostname) + + self._api = None + # autodetect the VAPIX API and connect to it; try it forever + while self._api is None and not rospy.is_shutdown(): try: - self.header[parts[0]] = parts[1] - except: - rospy.logwarn('Problem encountered with image header. Setting ' - 'content_length to zero') - self.header['Content-Length'] = 0 # set content_length to zero if - # there is a problem reading header - self.content_length = int(self.header['Content-Length']) - - def getImageData(self): - '''Get the binary image data itself (ie. without header)''' - if self.content_length>0: - self.img = self.fp.read(self.content_length) - self.fp.readline() # Read terminating \r\n and do nothing with it - - def publishMsg(self): - '''Publish jpeg image as a ROS message''' - self.msg = CompressedImage() - self.msg.header.stamp = rospy.Time.now() - self.msg.header.frame_id = self.axis.frame_id - self.msg.format = "jpeg" - self.msg.data = self.img - self.axis.pub.publish(self.msg) - - def publishCameraInfoMsg(self): - '''Publish camera info manager message''' - cimsg = self.axis.cinfo.getCameraInfo() - cimsg.header.stamp = self.msg.header.stamp - cimsg.header.frame_id = self.axis.frame_id - cimsg.width = self.axis.width - cimsg.height = self.axis.height - self.axis.caminfo_pub.publish(cimsg) - -class Axis: - def __init__(self, hostname, username, password, width, height, frame_id, - camera_info_url, use_encrypted_password): - self.hostname = hostname - self.username = username - self.password = password - self.width = width - self.height = height - self.frame_id = frame_id - self.camera_info_url = camera_info_url - self.use_encrypted_password = use_encrypted_password - + self._api = VAPIX.get_api_for_camera(hostname, username, password, camera_id, use_encrypted_password) + except (IOError, ValueError): + rospy.loginfo("Retrying connection to VAPIX on host %s, camera %d in 2 seconds." % + (hostname, camera_id)) + rospy.sleep(2) + if rospy.is_shutdown(): + return + + self._allowed_resolutions = self._get_allowed_resolutions() + + rospy.loginfo("The following resolutions are available for camera %d:\n%s" % + (camera_id, "\n".join([str(res) for res in self._allowed_resolutions]))) + rospy.set_param("~allowed_resolutions", [res.get_vapix_representation() for res in self._allowed_resolutions]) + + # Sometimes the camera falls into power saving mode and stops streaming. + # This setting allows the script to try to wake up the camera. + self._auto_wakeup_camera = auto_wakeup_camera + + # dynamic-reconfigurable properties - definitions + self._width = None # deprecated + self._height = None # deprecated + self._resolution = None + self._compression = None + self._fps = None + self._use_color = None + self._use_square_pixels = None + + # treat empty strings as None in width and height params + width = width if width != "" else None + height = height if height != "" else None + + # dynamic-reconfigurable properties - defaults + if width is None and height is None: + # TODO change to perform default resolution detection from VAPIX + self.set_resolution(self._allowed_resolutions[0]) + else: + resolution = self.find_resolution_by_size(width, height) + self.set_resolution(resolution.get_vapix_representation()) + + self.set_compression(compression) + self.set_fps(fps) + self.set_use_color(use_color) + self.set_use_square_pixels(use_square_pixels) + + # only advertise the supported resolutions on dynamic reconfigure + change_enum_items( + VideoStreamConfig, + "resolution", + [{ + 'name': res.name if isinstance(res, CIFVideoResolution) else str(res), + 'value': res.get_vapix_representation(), + 'description': str(res) + } for res in self._allowed_resolutions], + self._resolution.get_vapix_representation() + ) + + # dynamic reconfigure server + self._video_stream_param_change_server = dynamic_reconfigure.server.Server(VideoStreamConfig, + self.reconfigure_video) + + # camera info setup + self._frame_id = frame_id + self._camera_info_url = camera_info_url + # generate a valid camera name based on the hostname - self.cname = camera_info_manager.genCameraName(self.hostname) - self.cinfo = camera_info_manager.CameraInfoManager(cname = self.cname, - url = self.camera_info_url) - self.cinfo.loadCameraInfo() # required before getCameraInfo() - self.st = None - self.pub = rospy.Publisher("image_raw/compressed", CompressedImage, self) - self.caminfo_pub = rospy.Publisher("camera_info", CameraInfo, self) + self._camera_name = camera_info_manager.genCameraName(self._hostname) + self._camera_info = camera_info_manager.CameraInfoManager(cname=self._camera_name, url=self._camera_info_url) + self._camera_info.loadCameraInfo() # required before getCameraInfo() + + # the thread used for streaming images (is instantiated when the first image subscriber subscribes) + self._streaming_thread = None + + # the publishers are started/stopped lazily in peer_subscribe/peer_unsubscribe + self._video_publisher_frequency_diagnostic = FrequencyStatusParam({'min': self._fps, 'max': self._fps}) + self._video_publisher = PausableDiagnosedPublisher( + self, + rospy.Publisher("image_raw/compressed", CompressedImage, self, queue_size=100), + self.diagnostic_updater, self._video_publisher_frequency_diagnostic, TimeStampStatusParam() + ) + self._camera_info_publisher = PausableDiagnosedPublisher( + self, + rospy.Publisher("camera_info", CameraInfo, self, queue_size=100), + self.diagnostic_updater, self._video_publisher_frequency_diagnostic, TimeStampStatusParam() + ) + + self._snapshot_server = rospy.Service("take_snapshot", TakeSnapshot, self.take_snapshot) + + self.diagnostic_updater.add(FunctionDiagnosticTask("Camera parameters", self._camera_diagnostic_callback)) + + # BACKWARDS COMPATIBILITY LAYER + + self.username = username # deprecated + self.password = password # deprecated + self.use_encrypted_password = use_encrypted_password # deprecated + self.st = None # deprecated + self.pub = self._video_publisher # deprecated + self.caminfo_pub = self._camera_info_publisher # deprecated + + self.__initializing = False def __str__(self): - """Return string representation.""" - return(self.hostname + ',' + self.username + ',' + self.password + - '(' + str(self.width) + 'x' + str(self.height) + ')') + (width, height) = self._resolution.get_resolution(self._use_square_pixels) + return 'Axis driver on host %s, camera %d (%dx%d px @ %d FPS)' % \ + (self._hostname, self._api.camera_id, width, height, self._fps) def peer_subscribe(self, topic_name, topic_publish, peer_publish): - '''Lazy-start the image-publisher.''' - if self.st is None: - self.st = StreamThread(self) - self.st.start() + """Lazy-start the image-publisher.""" + if self._streaming_thread is None: + self._streaming_thread = ImageStreamingThread(self) + self._streaming_thread.start() + else: + self._streaming_thread.resume() + + def peer_unsubscribe(self, topic_name, num_peers): + """Lazy-stop the image-publisher when nobody is interested""" + if num_peers == 0: + self._streaming_thread.pause() + + def take_snapshot(self, request): + """Retrieve a snapshot from the camera. + + :param request: The service request. + :type request: :py:class:`axis_camera.srv.TakeSnapshotRequest` + :return: The response containing the image. + :rtype: :py:class:`axis_camera.srv.TakeSnapshotResponse` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` + """ + image_data = self._api.take_snapshot() + + image = CompressedImage() + + image.header.stamp = rospy.Time.now() + image.header.frame_id = self._frame_id + + image.format = "jpeg" + + image.data = image_data + + response = TakeSnapshotResponse() + response.image = image + + return response + + def reconfigure_video(self, config, level): + """Dynamic reconfigure callback for video parameters. + + :param config: The requested configuration. + :type config: dict + :param level: Unused here. + :type level: int + :return: The config corresponding to what was really achieved. + :rtype: dict + """ + if self.__initializing: + # in the initialization phase, we want to give precedence to the values given to the constructor + config.compression = self._compression + config.fps = self._fps + config.use_color = self._use_color + config.use_square_pixels = self._use_square_pixels + config.resolution = self._resolution.get_vapix_representation() + else: + self.__try_set_value_from_config(config, 'compression', self.set_compression) + self.__try_set_value_from_config(config, 'fps', self.set_fps) + self.__try_set_value_from_config(config, 'use_color', self.set_use_color) + self.__try_set_value_from_config(config, 'use_square_pixels', self.set_use_square_pixels) + + try: + self.set_resolution(config.resolution) + except ValueError: + config.resolution = self._resolution.get_vapix_representation() + + return config + + def __try_set_value_from_config(self, config, field, setter): + """First, try to call `setter(config[field])`, and if this call doesn't succeed. set the field in config to + its value stored in this class. + + :param config: The dynamic reconfigure config dictionary. + :type config: dict + :param field: The field name (both in :py:obj:`config` and in :py:obj:`self`). + :type field: basestring + :param setter: The setter to use to set the value. + :type setter: lambda function + """ + try: + setter(config[field]) + except ValueError: + config[field] = getattr(self, field) + + ################################# + # DYNAMIC RECONFIGURE CALLBACKS # + ################################# + + def set_resolution(self, resolution_value): + """Request a new resolution for the video stream. + + :param resolution_value: The string of type `width`x`height` or a :py:class:`VideoResolution` object. + :type resolution_value: basestring|VideoResolution + :raises: :py:exc:`ValueError` if the resolution is unknown/unsupported. + """ + resolution = None + if isinstance(resolution_value, VideoResolution): + resolution = resolution_value + elif isinstance(resolution_value, basestring): + resolution = self._get_resolution_from_param_value(resolution_value) + + if resolution is None: + raise ValueError("Unsupported resolution type specified: %r" % resolution_value) + + if self._resolution is None or resolution != self._resolution: + self._resolution = resolution + self.video_params_changed = True + # deprecated values + self._width = resolution.get_resolution(self._use_square_pixels)[0] + self._height = resolution.get_resolution(self._use_square_pixels)[1] + + def _get_resolution_from_param_value(self, value): + """Return a :py:class:`VideoResolution` object corresponding to the given video resolution param string. + + :param value: Value of the resolution parameter to parse (of form `width`x`height`). + :type value: basestring + :return: The :py:class:`VideoResolution` corresponding to the given resolution param string. + :rtype: :py:class:`VideoResolution` + :raises: :py:exc:`ValueError` if the resolution is unknown/unsupported. + """ + for resolution in self._allowed_resolutions: + if resolution.get_vapix_representation() == value: + return resolution + + raise ValueError("%s is not a valid valid resolution." % value) + + def find_resolution_by_size(self, width, height): + """Return a :py:class:`VideoResolution` object with the given dimensions. + + If there are more resolutions with the same size, any of them may be returned. + + :param width: Image width in pixels. If `None`, resolutions will be matched only by height. + :type width: int|None + :param height: Image height in pixels. If `None`, resolutions will be matched only by width. + :type height: int|None + :return: The corresponding resolution object. + :rtype: :py:class:`VideoResolution` + :raises: :py:exc:`ValueError` if no resolution with the given dimensions can be found. + :raises: :py:exc:`ValueError` if both `width` and `height` are None. + """ + if width is None and height is None: + raise ValueError("Either width or height of the desired resolution must be specified.") + + for resolution in self._allowed_resolutions: + size = resolution.get_resolution(use_square_pixels=False) + if (width is None or width == size[0]) and (height is None or height == size[1]): + return resolution + + size = resolution.get_resolution(use_square_pixels=True) + if (width is None or width == size[0]) and (height is None or height == size[1]): + return resolution + + raise ValueError("Cannot find a supported resolution with dimensions %sx%s" % (width, height)) + + def _get_allowed_resolutions(self): + """Return a list of resolutions supported both by the camera. + + :return: The supported resolutions list. + :rtype: list of :py:class:`VideoResolution` + """ + camera_resolutions = self._get_resolutions_supported_by_camera() + + return camera_resolutions + + def _get_resolutions_supported_by_camera(self): + """Return a list of resolutions supported the camera. + + :return: The supported resolutions list. + :rtype: list of :py:class:`VideoResolution` + """ + try: + names = self._api.parse_list_parameter_value(self._api.get_parameter("Properties.Image.Resolution")) + return [VideoResolution.parse_from_vapix_param_value(name, self._api) for name in names] + except (IOError, ValueError): + rospy.logwarn("Could not determine resolutions supported by the camera. Asssuming only CIF.") + return [CIFVideoResolution("CIF", 384, 288)] + + def set_compression(self, compression): + """Request the given compression level for the video stream. + + :param compression: Compression of the image (0 - no compression, 100 - max compression). + :type compression: int + :raises: :py:exc:`ValueError` if the given compression level is outside the allowed range. + """ + if compression != self._compression: + self._compression = self.sanitize_compression(compression) + self.video_params_changed = True + + @staticmethod + def sanitize_compression(compression): + """Make sure the given value can be used as a compression level of the video stream. + + :param compression: Compression of the image (0 - no compression, 100 - max compression). + :type compression: int + :return: The given compression converted to an int. + :rtype: int + :raises: :py:exc:`ValueError` if the given compression level is outside the allowed range. + """ + compression = int(compression) + if not (0 <= compression <= 100): + raise ValueError("%s is not a valid value for compression." % str(compression)) + + return compression + + def set_fps(self, fps): + """Request the given compression level for the video stream. + + :param fps: The desired frames per second. + :type fps: int + :raises: :py:exc:`ValueError` if the given FPS is outside the allowed range. + """ + if fps != self._fps: + self._fps = self.sanitize_fps(fps) + self.video_params_changed = True + if hasattr(self, "_video_publisher_frequency_diagnostic"): + self._video_publisher_frequency_diagnostic.freq_bound['min'] = self._fps + self._video_publisher_frequency_diagnostic.freq_bound['max'] = self._fps + + @staticmethod + def sanitize_fps(fps): + """Make sure the given value can be used as FPS of the video stream. + + :param fps: The desired frames per second. + :type fps: int + :return: The given FPS converted to an int. + :rtype: int + :raises: :py:exc:`ValueError` if the given FPS is outside the allowed range. + """ + fps = int(fps) + if not (1 <= fps <= 30): + raise ValueError("%s is not a valid value for FPS." % str(fps)) + + return fps + + def set_use_color(self, use_color): + """Request using/not using color in the video stream. + :param use_color: If True, send a color stream, otherwise send only grayscale image. + + :type use_color: bool + :raises: :py:exc:`ValueError` if the given argument is not a bool. + """ + if use_color != self._use_color: + self._use_color = self.sanitize_bool(use_color, "use_color") + self.video_params_changed = True + + def set_use_square_pixels(self, use_square_pixels): + """Request using/not using square pixels. + + :param use_square_pixels: If True, the resolution will be stretched to match 1:1 pixels. + By default, the pixels have a ratio of 11:12. + :type use_square_pixels: bool + :raises: :py:exc:`ValueError` if the given argument is not a bool. + """ + if use_square_pixels != self._use_square_pixels: + self._use_square_pixels = self.sanitize_bool(use_square_pixels, "use_square_pixels") + self.video_params_changed = True + + @staticmethod + def sanitize_bool(value, field_name): + """Convert the given value to a bool. + + :param value: Either True, False,, "1", "0", 1 or 0. + :type value: :py:class:`basestring` | :py:class:`bool` | :py:class:`int` + :param field_name: Name of the field this value belongs to (just for debug messages). + :type field_name: basestring + :return: The bool value of the given value. + :rtype: :py:class:`bool` + :raises: :py:exc:`ValueError` if the given value is not supported in this conversion. + """ + if value not in (True, False, "1", "0", 1, 0): + raise ValueError("%s is not a valid value for %s." % (str(value), field_name)) + + # bool("0") returns True because it is a nonempty string + if value == "0": + return False + + return bool(value) + + def _camera_diagnostic_callback(self, diag_message): + assert isinstance(diag_message, DiagnosticStatusWrapper) + + diag_message.summary(DiagnosticStatusWrapper.OK, "Video parameters") + diag_message.add("FPS", self._fps) + diag_message.add("Resolution", self._resolution) + diag_message.add("Compression", self._compression) + diag_message.add("Color image", self._use_color) + diag_message.add("Square pixels used", self._use_square_pixels) + + +class VideoResolution(object): + """A class representing a video resolution.""" + + def __init__(self, width, height): + """Create a representation of the resolution. + + :param width: Width of the resolution in pixels. + :type width: int + :param height: Height of the resolution in pixels. + :type height: int + """ + super(VideoResolution, self).__init__() + + self.width = int(width) + self.height = int(height) + + self.square_pixel_conversion_ratio_width = 12.0 / 11.0 + self.square_pixel_conversion_ratio_height = 1 + + def __str__(self): + return "%dx%d" % (self.width, self.height) + + def __repr__(self): + return "VideoResolution(width=%r,height=%r)" % (self.width, self.height) + + def __eq__(self, other): + # compare by attribute values + return self.__dict__ == other.__dict__ + + def __ne__(self, other): + # reuse the former __eq__ definition + return not self == other + + def get_resolution(self, use_square_pixels=False): + """Get the image dimensions corresponding to this resolution. + + :param use_square_pixels: Whether to strech the resulting resolution to square pixels. + :type use_square_pixels: bool + :return: A tuple (width, height) + :rtype: tuple + """ + width = self.width + height = self.height + + if use_square_pixels: + width = int(math.ceil(self.square_pixel_conversion_ratio_width * self.width)) + height = int(math.ceil(self.square_pixel_conversion_ratio_height * self.height)) + + return width, height + + def get_vapix_representation(self): + return "%dx%d" % (self.width, self.height) + + @staticmethod + def parse_from_vapix_param_value(value, api): + assert isinstance(value, basestring) + assert isinstance(api, VAPIX) + + numeric_regexp = re.compile(r"(\d+)x(\d+)") + match = numeric_regexp.match(value) + + if match is not None: + return VideoResolution(int(match.group(1)), int(match.group(2))) + else: # resolution given by CIF name + name = value + width, height = api.resolve_video_resolution_name(name) + return CIFVideoResolution(name, width, height) + + +class CIFVideoResolution(VideoResolution): + """A class representing a CIF standard resolution.""" + + def __init__(self, name, width, height): + """Create a representation of a CIF resolution. + + :param name: CIF standard name of the resolution. + :type name: basestring + :param width: Width of the resolution in pixels. + :type width: int + :param height: Height of the resolution in pixels. + :type height: int + """ + super(CIFVideoResolution, self).__init__(width, height) + + self.name = name + + def __str__(self): + return "%s (%dx%d)" % (self.name, self.width, self.height) + + def __repr__(self): + return "CIFVideoResolution(name=%r,width=%r,height=%r)" % (self.name, self.width, self.height) def main(): + """Start the ROS driver and ROS node.""" rospy.init_node("axis_driver") arg_defaults = { 'hostname': '192.168.0.90', # default IP address - 'username': 'root', # default login name - 'password': '', - 'width': 640, - 'height': 480, + 'username': None, # default login name + 'password': None, + 'width': 704, + 'height': 576, 'frame_id': 'axis_camera', 'camera_info_url': '', - 'use_encrypted_password' : False} - args = updateArgs(arg_defaults) - Axis(**args) - rospy.spin() - -def updateArgs(arg_defaults): - '''Look up parameters starting in the driver's private parameter space, but - also searching outer namespaces. Defining them in a higher namespace allows - the axis_ptz.py script to share parameters with the driver.''' + 'use_encrypted_password': False, + 'camera_id': 1, + 'auto_wakeup_camera': True, + 'compression': 0, + 'fps': 24, + 'use_color': True, + 'use_square_pixels': False, + } + args = read_args_with_defaults(arg_defaults) + axis = Axis(**args) + + rate = rospy.Rate(1) + + while not rospy.is_shutdown(): + axis.diagnostic_updater.update() + try: + rate.sleep() + except rospy.ROSTimeMovedBackwardsException: + rospy.logwarn("Detected jump back in time.") + + +class PausableDiagnosedPublisher(DiagnosedPublisher): + def __init__(self, axis, pub, diag, freq, stamp): + DiagnosedPublisher.__init__(self, pub, diag, freq, stamp) + self._axis = axis + + def run(self, stat): + if self._axis._streaming_thread is None or self._axis._streaming_thread.is_paused(): + stat.summary(DiagnosticStatusWrapper.OK, "Video not subscribed") + else: + stat = DiagnosedPublisher.run(self, stat) + return stat + + +def read_args_with_defaults(arg_defaults): + """Look up parameters starting in the driver's private parameter space, but also searching outer namespaces. + Defining them in a higher namespace allows the axis_ptz.py script to share parameters with the driver.""" args = {} for name, val in arg_defaults.iteritems(): full_name = rospy.search_param(name) @@ -204,7 +644,7 @@ def updateArgs(arg_defaults): if prefix_val[0] != '/': # prefix not absolute? prefix_val = '/' + prefix_val args['frame_id'] = prefix_val + '/' + args['frame_id'] - return(args) + return args if __name__ == "__main__": main() diff --git a/nodes/axis_ptz.py b/nodes/axis_ptz.py index bf54209..fa74504 100755 --- a/nodes/axis_ptz.py +++ b/nodes/axis_ptz.py @@ -1,138 +1,138 @@ #!/usr/bin/env python # -# Basic PTZ node, based on documentation here: -# http://www.axis.com/files/manuals/vapix_ptz_45621_en_1112.pdf -# +# Basic VAPIX PTZ node, based on documentation here: +# http://www.axis.com/global/en/support/developer-support/vapix + import threading -import httplib, urllib -import rospy + +import rospy from axis_camera.msg import Axis from std_msgs.msg import Bool -import math from dynamic_reconfigure.server import Server from axis_camera.cfg import PTZConfig -class StateThread(threading.Thread): - '''This class handles the publication of the positional state of the camera - to a ROS message''' - - def __init__(self, axis): - threading.Thread.__init__(self) - self.axis = axis - # Permit program to exit even if threads are still running by flagging - # thread as a daemon: - self.daemon = True - - def run(self): - r = rospy.Rate(1) - self.msg = Axis() - - while True: - self.queryCameraPosition() - self.publishCameraState() - r.sleep() - - def queryCameraPosition(self): - '''Using Axis VAPIX protocol, described in the comments at the top of - this file, is used to query the state of the camera''' - conn = httplib.HTTPConnection(self.axis.hostname) - queryParams = { 'query':'position' } - try: - conn.request("GET", "/axis-cgi/com/ptz.cgi?%s" % - urllib.urlencode(queryParams)) - response = conn.getresponse() - # Response code 200 means there are data to be read: - if response.status == 200: - body = response.read() - new_camera_position = dict() - for s in body.splitlines(): - field_and_value = s.split('=', 2) - if len(field_and_value) == 2: - # On some PTZ cameras (AXIS 212 PTZ for example) - # The returning string has a newline at the end - # so if we don't have a field AND value, don't insert - new_camera_position[field_and_value[0]] = field_and_value[1] - self.cameraPosition = new_camera_position - # Response code 401 means authentication error - elif response.status == 401: - rospy.logwarn('You need to enable anonymous PTZ control login' - 'at http://%s -> Setup Basic Setup -> Users' % self.hostname) - else: - self.cameraPosition = None - rospy.logwarn('Received HTTP response %i from camera, expecting 200' % response.status) - except Exception as e: - exception_error_str = "Exception: '" + str(e) + "' when querying the url: http://" + \ - self.axis.hostname + "/axis-cgi/com/ptz.cgi?%s" % urllib.urlencode(queryParams) - rospy.logwarn(exception_error_str) - - self.cameraPosition = None - - def publishCameraState(self): - '''Publish camera state to a ROS message''' - if self.cameraPosition is not None: - self.msg.pan = float(self.cameraPosition['pan']) - if self.axis.flip: - self.adjustForFlippedOrientation() - self.msg.tilt = float(self.cameraPosition['tilt']) - self.msg.zoom = float(self.cameraPosition['zoom']) - self.msg.iris = 0.0 - if 'iris' in self.cameraPosition: - self.msg.iris = float(self.cameraPosition['iris']) - self.msg.focus = 0.0 - if 'focus' in self.cameraPosition: - self.msg.focus = float(self.cameraPosition['focus']) - if 'autofocus' in self.cameraPosition: - self.msg.autofocus = (self.cameraPosition['autofocus'] == 'on') - self.axis.pub.publish(self.msg) - - def adjustForFlippedOrientation(self): - '''Correct pan and tilt parameters if camera is mounted backwards and - facing down''' - self.msg.pan = 180 - self.msg.pan - if self.msg.pan > 180: - self.msg.pan -= 360 - elif self.msg.pan < -180: - self.msg.pan += 360 - self.msg.tilt = -self.msg.tilt +from axis_camera.vapix import VAPIX +from axis_camera.position_streaming import PositionStreamingThread +from axis_camera.camera_control import AxisCameraController + +StateThread = PositionStreamingThread # deprecated + class AxisPTZ: - '''This class creates a node to manage the PTZ functions of an Axis PTZ - camera''' - def __init__(self, hostname, username, password, flip, speed_control): - self.hostname = hostname - self.username = username - self.password = password - self.flip = flip - # speed_control is true for speed control and false for - # position control: - self.speedControl = speed_control - self.mirror = False - - self.st = None - self.pub = rospy.Publisher("state", Axis, self) - self.sub = rospy.Subscriber("cmd", Axis, self.cmd, queue_size=1) - self.sub_mirror = rospy.Subscriber("mirror", Bool, self.mirrorCallback, - queue_size=1) - - def peer_subscribe(self, topic_name, topic_publish, peer_publish): - '''Lazy-start the state publisher.''' - if self.st is None: - self.st = StateThread(self) - self.st.start() - - def cmd(self, msg): - '''Command the camera with speed control or position control commands''' - self.msg = msg - if self.flip: - self.adjustForFlippedOrientation() - if self.mirror: - self.msg.pan = -self.msg.pan + """This class is a node to manage the PTZ functions of an Axis PTZ camera. The most of its work is done by + :py:class:`AxisCameraController ` and this is just a ROS node + envelope. + """ + + def __init__(self, hostname, username, password, flip, speed_control, frame_id="axis_camera", + use_encrypted_password=False, state_publishing_frequency=50, camera_id=1): + """Initialize the PTZ driver and start publishing positional data. + + :param hostname: Hostname of the camera (without http://, can be an IP address). + :type hostname: basestring + :param username: If login is needed, provide a username here. + :type username: basestring|None + :param password: If login is needed, provide a password here. + :type password: basestring|None + :param flip: Whether to flip the controls (for ceiling-mounted cameras). Deprecated. + :type flip: bool + :param speed_control: Use speed control instead of positional. Deprecated. + :type speed_control: bool + :param frame_id: Id of the frame in which positinal data should be published. + :type frame_id: basestring + :param use_encrypted_password: Whether to use Plain HTTP Auth (False) or Digest HTTP Auth (True). + :type use_encrypted_password: bool + :param state_publishing_frequency: The frequency at which joint states should be published. + :type state_publishing_frequency: int + :param camera_id: ID (number) of the camera. Can be 1 to 4. + :type camera_id: int + """ + + self._hostname = hostname + self._camera_id = camera_id + self._frame_id = frame_id + + self._state_publishing_frequency = state_publishing_frequency + + self._executing_reconfigure = False + self._reconfigure_mutex = threading.Lock() + + self._api = None + # autodetect the VAPIX API and connect to it; try it forever + while self._api is None and not rospy.is_shutdown(): + try: + self._api = VAPIX.get_api_for_camera(hostname, username, password, camera_id, use_encrypted_password) + except (IOError, ValueError): + rospy.loginfo( + "Retrying connection to VAPIX on host %s, camera %d in 2 seconds." % (hostname, camera_id)) + rospy.sleep(2) + if rospy.is_shutdown(): + return + + if not self._api.has_ptz(): + raise RuntimeError("Camera %d on host %s doesn't have a Pan-Tilt-Zoom unit." % (self._camera_id, self._hostname)) + + # Create a controller of the camera + self._camera_controller = AxisCameraController(self._api, self, flip_vertically=flip, flip_horizontally=flip) + + # BACKWARDS COMPATIBILITY LAYER + self.username = username # deprecated + self.password = password # deprecated + self.flip = flip # deprecated + self.speedControl = speed_control # deprecated + self.mirror = False # deprecated + + self.msg = None # deprecated + self.cmdString = "" # deprecated + + self.pub = rospy.Publisher("state", Axis, queue_size=100) # deprecated + self.command_subscriber = rospy.Subscriber("cmd", Axis, self.cmd, queue_size=100) # deprecated + self.mirror_subscriber = rospy.Subscriber("mirror", Bool, self.mirrorCallback, queue_size=100) # deprecated + + self.srv = Server(PTZConfig, self.callback) # deprecated + + # Needs to be after the backwards compatibility setup + # start the publisher thread + self._publisher_thread = PositionStreamingThread(self, self._api) + self.st = self._publisher_thread # deprecated + self._publisher_thread.start() + + # BACKWARDS COMPATIBILITY LAYER + + def cmd(self, message): + """Deprecated.""" + self.msg = message + self.sanitisePTZCommands() - self.applySetpoints() + + if self._api.has_capabilities('AbsolutePan', 'AbsoluteTilt', 'AbsoluteZoom'): + self._camera_controller.set_ptz(message.pan, message.tilt, message.zoom) + else: + rospy.loginfo("Camera on host %s doesn't support PTZ control." % self._hostname) + + if self._api.has_capability('AbsoluteFocus'): + self._camera_controller.set_focus(message.focus, set_also_autofocus=False) + else: + rospy.loginfo("Camera on host %s doesn't support absolute focus control." % self._hostname) + + if self._api.has_capability('AutoFocus'): + if message.focus != self._camera_controller._focus: + self._camera_controller.set_autofocus(False) + else: + self._camera_controller.set_autofocus(message.autofocus) + else: + rospy.loginfo("Camera on host %s doesn't support autofocus." % self._hostname) + + if self._api.has_capability('AutoIris'): + self._camera_controller.set_autoiris(True) + else: + rospy.loginfo("Camera on host %s doesn't support autoiris." % self._hostname) + + # there is no capability for brightness + self._camera_controller.set_brightness(message.brightness) def adjustForFlippedOrientation(self): - '''If camera is mounted backwards and upside down (ie. self.flip==True - then apply appropriate transforms to pan and tilt''' + """Deprecated.""" self.msg.tilt = -self.msg.tilt if self.speedControl: self.msg.pan = -self.msg.pan @@ -140,167 +140,182 @@ def adjustForFlippedOrientation(self): self.msg.pan = 180.0 - self.msg.pan def sanitisePTZCommands(self): - '''Applies limits to message and corrects for flipped camera if - necessary''' - self.sanitisePan() - self.sanitiseTilt() - self.sanitiseZoom() - self.sanitiseFocus() - self.sanitiseBrightness() - self.sanitiseIris() + """Deprecated.""" + if not self.speedControl: + self.msg.pan = self._api.ptz_limits['Pan'].absolute.crop_value(self.msg.pan) + self.msg.tilt = self._api.ptz_limits['Tilt'].absolute.crop_value(self.msg.tilt) + self.msg.zoom = self._api.ptz_limits['Zoom'].absolute.crop_value(self.msg.zoom) + self.msg.focus = self._api.ptz_limits['Focus'].absolute.crop_value(self.msg.focus) + self.msg.brightness = self._api.ptz_limits['Brightness'].absolute.crop_value(self.msg.brightness) + self.msg.iris = self._api.ptz_limits['Iris'].absolute.crop_value(self.msg.iris) + else: + self.msg.pan = self._api.ptz_limits['Pan'].velocity.crop_value(self.msg.pan) + self.msg.tilt = self._api.ptz_limits['Tilt'].velocity.crop_value(self.msg.tilt) + self.msg.zoom = self._api.ptz_limits['Zoom'].velocity.crop_value(self.msg.zoom) + self.msg.focus = self._api.ptz_limits['Focus'].velocity.crop_value(self.msg.focus) + self.msg.brightness = self._api.ptz_limits['Brightness'].velocity.crop_value(self.msg.brightness) + self.msg.iris = self._api.ptz_limits['Iris'].velocity.crop_value(self.msg.iris) def sanitisePan(self): - '''Pan speed (in percent) must be: -100100.0: - self.msg.pan = math.copysign(100.0, self.msg.pan) - else: # position control so need to ensure -180100.0: - self.msg.tilt = math.copysign(100.0, self.msg.tilt) - else: # position control so ensure tilt: -180100: - self.msg.zoom = math.copysign(100.0, self.msg.zoom) - else: # position control: - if self.msg.zoom>9999.0: - self.msg.zoom = 9999.0 - elif self.msg.zoom<1.0: - self.msg.zoom = 1.0 + self.msg.zoom = self._api.ptz_limits['Zoom'].velocity.crop_value(self.msg.zoom) + else: + self.msg.zoom = self._api.ptz_limits['Zoom'].absolute.crop_value(self.msg.zoom) def sanitiseFocus(self): - '''Focus must be: 1100.0: - self.msg.focus = math.copysign(100.0, self.msg.focus) - else: # position control: - if self.msg.focus>9999.0: - self.msg.focus = 9999.0 - elif self.msg.focus < 1.0: - self.msg.focus = 1.0 + self.msg.focus = self._api.ptz_limits['Focus'].velocity.crop_value(self.msg.focus) + else: + self.msg.focus = self._api.ptz_limits['Focus'].absolute.crop_value(self.msg.focus) def sanitiseBrightness(self): - '''Brightness must be: 1 100.0: - self.msg.brightness = math.copysign(100.0, self.msg.brightness) - else: # position control: - if self.msg.brightness>9999.0: - self.msg.brightness = 9999.0 - elif self.msg.brightness<1.0: - self.msg.brightness = 1.0 + self.msg.brightness = self._api.ptz_limits['Brightness'].velocity.crop_value(self.msg.brightness) + else: + self.msg.brightness = self._api.ptz_limits['Brightness'].absolute.crop_value(self.msg.brightness) def sanitiseIris(self): - '''Iris value is read only because autoiris has been set to "on"''' - if self.msg.iris>0.000001: + """Deprecated.""" + if self.msg.iris > 0.000001: rospy.logwarn("Iris value is read-only.") def applySetpoints(self): - '''Apply set-points to camera via HTTP''' - conn = httplib.HTTPConnection(self.hostname) - self.createCmdString() - try: - conn.request('GET', self.cmdString) - except: - rospy.logwarn('Failed to connect to camera to send command message') - conn.close() + """Deprecated.""" + """Apply the command to the camera using the HTTP API""" + self._camera_controller.set_ptz(self.msg.pan, self.msg.tilt, self.msg.zoom) + self._camera_controller.set_autofocus(self.msg.autofocus) + if not self.msg.autofocus: + self._camera_controller.set_focus(self.msg.focus) + self._camera_controller.set_autoiris(True) + self._camera_controller.set_brightness(self.msg.brightness) def createCmdString(self): - '''creates http cgi string to command PTZ camera''' + """Deprecated.""" + """Created tje HTTP API string to command PTZ camera""" self.cmdString = '/axis-cgi/com/ptz.cgi?' if self.speedControl: - self.cmdString += 'continuouspantiltmove=%d,%d&' % \ - (int(self.msg.pan), int(self.msg.tilt)) \ - + 'continuouszoommove=%d&' % (int(self.msg.zoom)) \ - + 'continuousbrightnessmove=%d&' % \ - (int(self.msg.brightness)) + self.cmdString += 'continuouspantiltmove=%d,%d&' % (int(self.msg.pan), int(self.msg.tilt)) + self.cmdString += 'continuouszoommove=%d&' % self.msg.zoom + self.cmdString += 'continuousbrightnessmove=%d&' % self.msg.brightness # Note that brightness adjustment has no effect for Axis 214PTZ. if self.msg.autofocus: self.cmdString += 'autofocus=on&' else: - self.cmdString += 'autofocus=off&continuousfocusmove=%d&' % \ - (int(self.msg.focus)) + self.cmdString += 'autofocus=off&continuousfocusmove=%d&' % self.msg.focus self.cmdString += 'autoiris=on' else: # position control: - self.cmdString += 'pan=%d&tilt=%d&' % (self.msg.pan, self.msg.tilt)\ - + 'zoom=%d&' % (int(self.msg.zoom)) \ - + 'brightness=%d&' % (int(self.msg.brightness)) + self.cmdString += 'pan=%f&tilt=%f&' % (self.msg.pan, self.msg.tilt) + self.cmdString += 'zoom=%d&' % self.msg.zoom + self.cmdString += 'brightness=%d&' % self.msg.brightness if self.msg.autofocus: self.cmdString += 'autofocus=on&' else: - self.cmdString += 'autofocus=off&focus=%d&' % \ - (int(self.msg.focus)) + self.cmdString += 'autofocus=off&focus=%d&' % self.msg.focus self.cmdString += 'autoiris=on' def mirrorCallback(self, msg): + """Deprecated.""" '''Command the camera with speed control or position control commands''' self.mirror = msg.data + self._camera_controller.mirror_horizontally = self.mirror def callback(self, config, level): + """Deprecated.""" #self.speedControl = config.speed_control - - # create temporary message and fill with data from dynamic reconfigure - temp_msg = Axis() - temp_msg.pan = config.pan - temp_msg.tilt = config.tilt - temp_msg.zoom = config.zoom - temp_msg.focus = config.focus - temp_msg.brightness = config.brightness - temp_msg.autofocus = config.autofocus - - # check sanity and apply values - self.cmd(temp_msg) - - # read sanitized values and update GUI - config.pan = self.msg.pan - config.tilt = self.msg.tilt - config.zoom = self.msg.zoom - config.focus = self.msg.focus - config.brightness = self.msg.brightness - config.autofocus = self.msg.autofocus - - # update GUI with sanitized values - return config + + if self._executing_reconfigure or (hasattr(self, '_camera_controller') and (self._camera_controller._executing_parameter_update or self._camera_controller._executing_reconfigure)): + return config + + with self._reconfigure_mutex: + self._executing_reconfigure = True + + # create temporary message and fill with data from dynamic reconfigure + command = Axis() + command.pan = config.pan + command.tilt = config.tilt + command.zoom = config.zoom + command.focus = config.focus + command.brightness = config.brightness + command.autofocus = config.autofocus + + # check sanity and apply values + self.cmd(command) + + # read sanitized values and update GUI + config.pan = command.pan + config.tilt = command.tilt + config.zoom = command.zoom + config.focus = self._camera_controller._focus + config.brightness = self._camera_controller._brightness + config.autofocus = self._camera_controller._autofocus + + self._executing_reconfigure = False + + # update GUI with sanitized values + return config + def main(): - rospy.init_node("axis_twist") + rospy.init_node("axis_ptz_driver") arg_defaults = { 'hostname': '192.168.0.90', - 'username': '', - 'password': '', - 'flip': False, # things get weird if flip=true - 'speed_control': False + 'username': None, + 'password': None, + 'flip': False, + 'speed_control': False, + 'frame_id': 'axis_camera', + 'use_encrypted_password': False, + 'state_publishing_frequency': 50, + 'camera_id': 1, } - args = {} - - # go through all arguments - for name in arg_defaults: - full_param_name = rospy.search_param(name) - # make sure argument was found (https://github.com/ros/ros_comm/issues/253) - if full_param_name == None: - args[name] = arg_defaults[name] - else: - args[name] = rospy.get_param(full_param_name, arg_defaults[name]) + args = read_args_with_defaults(arg_defaults) - # create new PTZ object and start dynamic_reconfigure server + # Start the driver my_ptz = AxisPTZ(**args) - srv = Server(PTZConfig, my_ptz.callback) + rospy.spin() + +def read_args_with_defaults(arg_defaults): + """Look up parameters starting in the driver's private parameter space, but + also searching outer namespaces. Defining them in a higher namespace allows + the axis_ptz.py script to share parameters with the driver.""" + args = {} + for name, val in arg_defaults.iteritems(): + full_name = rospy.search_param(name) + if full_name is None: + args[name] = val + else: + args[name] = rospy.get_param(full_name, val) + # resolve frame_id with tf_prefix (unless already absolute) + if 'frame_id' in args and args['frame_id'][0] != '/': # not absolute? + tf_prefix = rospy.search_param('tf_prefix') + prefix_val = '' + if tf_prefix is not None: # prefix defined? + prefix_val = rospy.get_param(tf_prefix) + if prefix_val[0] != '/': # prefix not absolute? + prefix_val = '/' + prefix_val + args['frame_id'] = prefix_val + '/' + args['frame_id'] + return args + + if __name__ == "__main__": main() - \ No newline at end of file diff --git a/nodes/keyboard_teleop.py b/nodes/keyboard_teleop.py new file mode 100755 index 0000000..82ee247 --- /dev/null +++ b/nodes/keyboard_teleop.py @@ -0,0 +1,98 @@ +#!/usr/bin/env python +""" +Keyboard teleoperation node for the Axis camera. + +Use WSAD to control pan-tilt, and QE to control zoom. Shift increases speed. +Do not hold the buttons all the time, the commands need some time to get executed. +""" + +import rospy + +from axis_camera.msg import PTZ + +import sys, select, termios, tty +from std_msgs.msg import Header + +msg = """ +Reading from the keyboard and Publishing to Twist! +--------------------------- +Moving around: + q w e + a s d + +q/e: zoom +a/d: pan +w/s: tilt +Shift modifier: faster + +space: 0,0,0 position + + +CTRL-C to quit +""" + +moveBindings = { + 'a': (-1, 0, 0), + 'd': (1, 0, 0), + 's': (0, -1, 0), + 'w': (0, 1, 0), + 'q': (0, 0, -100), + 'e': (0, 0, 100), + 'A': (-10, 0, 0), + 'D': (10, 0, 0), + 'S': (0, -10, 0), + 'W': (0, 10, 0), + 'Q': (0, 0, -1000), + 'E': (0, 0, 1000), + ' ': None, +} + + +def get_key(): + """ + Read a key typed to the terminal. + :return: The key that was typed. + :rtype: basestring + """ + tty.setraw(sys.stdin.fileno()) + select.select([sys.stdin], [], [], 0) + key = sys.stdin.read(1) + new_settings = termios.tcgetattr(sys.stdin) + new_settings[3] = new_settings[3] & ~termios.ICANON & ~termios.ECHO + termios.tcsetattr(sys.stdin, termios.TCSADRAIN, new_settings) + return key + +if __name__ == "__main__": + # save current terminal settings + settings = termios.tcgetattr(sys.stdin) + + rospy.init_node('axis_keyboard_teleop') + + absolutePtzPublisher = rospy.Publisher('axis/control/pan_tilt_zoom/absolute', PTZ, queue_size=10) + relativePtzPublisher = rospy.Publisher('axis/control/pan_tilt_zoom/relative', PTZ, queue_size=10) + + print msg + + rate = rospy.Rate(1) + + try: + while not rospy.is_shutdown(): + key = get_key() + if key in moveBindings.keys(): + if moveBindings[key] is None: + absolutePtzPublisher.publish(PTZ(Header(), 0, 0, 0)) + else: + pan = moveBindings[key][0] + tilt = moveBindings[key][1] + zoom = moveBindings[key][2] + + relativePtzPublisher.publish(PTZ(Header(), pan, tilt, zoom)) + + elif key == '\x03': + break + + rate.sleep() + except Exception as e: + print e + finally: + termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings) diff --git a/nodes/publish_axis_tf.py b/nodes/publish_axis_tf.py deleted file mode 100755 index 97b1a1e..0000000 --- a/nodes/publish_axis_tf.py +++ /dev/null @@ -1,35 +0,0 @@ -#!/usr/bin/env python - -import rospy -import math -from axis_camera.msg import Axis -import tf -from tf.transformations import quaternion_from_euler - -base_name = "/kingfisher" -base_frame = "/kingfisher/base" -broadcaster = tf.TransformBroadcaster() - -def axis_cb(data): - global broadcaster, base_frame, base_name - pan = math.pi + data.pan * math.pi / 180. - tilt = -data.tilt * math.pi / 180. - q = quaternion_from_euler(0,0,pan) - now = rospy.Time.now() - broadcaster.sendTransform((0,0,0), - q,now,base_name+"/pan",base_frame) - q = quaternion_from_euler(0,tilt,0) - broadcaster.sendTransform((0,0,0), - q,now,base_name+"/tilt",base_name+"/pan") - - -if __name__ == '__main__': - try: - rospy.init_node("axis_tf_broadcaster") - base_frame = rospy.get_param("~base_frame",base_frame) - base_name = rospy.get_param("~base_name",base_name) - axis_sub = rospy.Subscriber("/axis/state",Axis,axis_cb) - rospy.loginfo("Started Axis TF broadcaster") - rospy.spin() - except rospy.ROSInterruptException: - pass diff --git a/package.xml b/package.xml index d01bde7..fe5c873 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ axis_camera - 0.2.0 + 0.3.0 Python ROS drivers for accessing an Axis camera's MJPG stream. Also provides control for PTZ cameras. @@ -17,20 +17,28 @@ catkin camera_info_manager_py - geometry_msgs + diagnostic_aggregator + diagnostic_msgs + diagnostic_updater + dynamic_reconfigure message_generation + python-catkin-pkg rospy sensor_msgs + std_msgs tf - dynamic_reconfigure + xacro camera_info_manager_py - geometry_msgs + diagnostic_aggregator + diagnostic_msgs + diagnostic_updater + dynamic_reconfigure message_runtime rospy sensor_msgs + std_msgs tf - dynamic_reconfigure diff --git a/rosdoc.yaml b/rosdoc.yaml index 1bda6fb..0136cd7 100644 --- a/rosdoc.yaml +++ b/rosdoc.yaml @@ -1,4 +1,4 @@ - builder: sphinx name: Python API output_dir: python - + sphinx_root_dir: doc diff --git a/scripts/axis_camera/__init__.py b/scripts/axis_camera/__init__.py new file mode 100644 index 0000000..c60310e --- /dev/null +++ b/scripts/axis_camera/__init__.py @@ -0,0 +1,4 @@ +import vapix +import video_streaming +import camera_control +import position_streaming diff --git a/scripts/axis_camera/camera_control.py b/scripts/axis_camera/camera_control.py new file mode 100644 index 0000000..be88896 --- /dev/null +++ b/scripts/axis_camera/camera_control.py @@ -0,0 +1,1083 @@ +import rospy +import threading + +from std_msgs.msg import Bool, Float32, Int32 +from diagnostic_updater import Updater, DiagnosticStatusWrapper, FunctionDiagnosticTask + +from axis_camera.cfg import CameraConfig +from axis_camera.msg import PTZ, PointInRectangle +# we already run one Server in axis_ptz for backwards compatibility, so we need to use a custom one allowing for subnamsepacing +# TODO remove this once the backwards compatibility layer is thrown away +from axis_camera.dynamic_reconfigure_server2 import Server + + +class AxisCameraController(object): + """A class serving as the Python and ROS controller of the Axis camera. + + It provides numerous topics/methods using which the camera can be controlled via VAPIX. + Each topic is only subscribed if the camera reports capabilities required for executing the topic's functionality. + + Currently provided topics are: + + - control/pan_tilt_zoom/absolute + - control/pan_tilt_zoom/relative + - control/pan_tilt_zoom/velocity + - control/pan_tilt/absolute + - control/pan_tilt/relative + - control/pan_tilt/velocity + - control/pan/absolute + - control/tilt/absolute + - control/zoom/absolute + - control/pan/relative + - control/tilt/relative + - control/zoom/relative + - control/pan/velocity + - control/tilt/velocity + - control/zoom/velocity + - control/look_at + - control/camera/focus/auto + - control/camera/focus/absolute + - control/camera/focus/relative + - control/camera/focus/velocity + - control/camera/iris/auto + - control/camera/iris/absolute + - control/camera/iris/relative + - control/camera/iris/velocity + - control/camera/brightness/absolute + - control/camera/brightness/relative + - control/camera/brightness/velocity + - control/camera/backlight_compensation + - control/camera/ir_cut_filter/auto + - control/camera/ir_cut_filter/use + """ + + def __init__(self, api, axis, flip_vertically=False, flip_horizontally=False, mirror_horizontally=False): + """Create the controller. + + :param api: The VAPIX instance to be used to communicate with the camera. + :type api: :py:class:`axis_camera.VAPIX` + :param axis: The parameter holding class. + :type axis: axis.Axis + :param flip_vertically: If True, flip the controls vertically (for ceiling mounted cameras). + :type flip_vertically: bool + :param flip_horizontally: If True, flip the controls horizontally (for ceiling mounted cameras). + :type flip_horizontally: bool + :param mirror_horizontally: If True, mirror the controls horizontally (for backwards mounted cameras). + :type mirror_horizontally: bool + """ + self._api = api + self._axis = axis + self._flip_vertically = flip_vertically + self._flip_horizontally = flip_horizontally + self._mirror_horizontally = mirror_horizontally + + self._parameter_update_mutex = threading.Lock() + self._executing_parameter_update = False + self._reconfigure_mutex = threading.Lock() + self._executing_reconfigure = False + + self._autofocus = True + self._focus = 0 + self._autoiris = True + self._iris = 0 + self._brightness = 5000 + self._backlight = False + self._ir_cut_filter = True + + self._dynamic_reconfigure_server = Server(CameraConfig, self._reconfigure, "axis_ptz_driver") + + self._diagnostic_updater = Updater() + self._diagnostic_updater.setHardwareID(api.hostname) + self._diagnostic_updater.add(FunctionDiagnosticTask("Last command status", self._diagnostic_last_command)) + self._last_command_error = None + + timer = rospy.Timer(rospy.Duration(1), lambda (event): self._diagnostic_updater.update()) + + # set up the topics this node listens on + # the callbacks are created as lambda wrappers around the Python API functions of this controller so that we + # do not blow this file with more unnecessary methods + if self._api.has_capabilities('AbsolutePan', 'AbsoluteTilt', 'AbsoluteZoom'): + self._absolute_ptz_subscriber = rospy.Subscriber( + "control/pan_tilt_zoom/absolute", PTZ, self._call_with_ptz_message(self.set_ptz), queue_size=100) + + if self._api.has_capabilities('RelativePan', 'RelativeTilt', 'RelativeZoom'): + self._relative_ptz_subscriber = rospy.Subscriber( + "control/pan_tilt_zoom/relative", PTZ, self._call_with_ptz_message(self.adjust_ptz), queue_size=100) + + if self._api.has_capabilities('ContinuousPan', 'ContinuousTilt', 'ContinuousZoom'): + self._velocity_ptz_subscriber = rospy.Subscriber( + "control/pan_tilt_zoom/velocity", PTZ, self._call_with_ptz_message(self.set_ptz_velocity), + queue_size=100) + + if self._api.has_capabilities('AbsolutePan', 'AbsoluteTilt'): + self._absolute_pan_tilt_subscriber = rospy.Subscriber( + "control/pan_tilt/absolute", PTZ, self._call_with_pt_message(self.set_pan_tilt), queue_size=100) + + if self._api.has_capabilities('RelativePan', 'RelativeTilt'): + self._relative_pan_tilt_subscriber = rospy.Subscriber( + "control/pan_tilt/relative", PTZ, self._call_with_pt_message(self.adjust_pan_tilt), queue_size=100) + + if self._api.has_capabilities('ContinuousPan', 'ContinuousTilt'): + self._velocity_pan_tilt_subscriber = rospy.Subscriber( + "control/pan_tilt/velocity", PTZ, self._call_with_pt_message(self.set_pan_tilt_velocity), + queue_size=100) + + if self._api.has_capability('AbsolutePan'): + self._absolute_pan_subscriber = rospy.Subscriber( + "control/pan/absolute", Float32, self._call_with_simple_message_data(self.set_pan), queue_size=100) + + if self._api.has_capability('AbsoluteTilt'): + self._absolute_tilt_subscriber = rospy.Subscriber( + "control/tilt/absolute", Float32, self._call_with_simple_message_data(self.set_tilt), queue_size=100) + + if self._api.has_capability('AbsoluteZoom'): + self._absolute_zoom_subscriber = rospy.Subscriber( + "control/zoom/absolute", Int32, self._call_with_simple_message_data(self.set_zoom), queue_size=100) + + if self._api.has_capability('RelativePan'): + self._relative_pan_subscriber = rospy.Subscriber( + "control/pan/relative", Float32, self._call_with_simple_message_data(self.adjust_pan), queue_size=100) + + if self._api.has_capability('RelativeTilt'): + self._relative_tilt_subscriber = rospy.Subscriber( + "control/tilt/relative", Float32, self._call_with_simple_message_data(self.adjust_tilt), queue_size=100) + + if self._api.has_capability('RelativeZoom'): + self._relative_zoom_subscriber = rospy.Subscriber( + "control/zoom/relative", Int32, self._call_with_simple_message_data(self.adjust_zoom), queue_size=100) + + if self._api.has_capability('ContinuousPan'): + self._pan_velocity_subscriber = rospy.Subscriber( + "control/pan/velocity", Int32, self._call_with_simple_message_data(self.set_pan_velocity), + queue_size=100) + + if self._api.has_capability('ContinuousTilt'): + self._tilt_velocity_subscriber = rospy.Subscriber( + "control/tilt/velocity", Int32, + self._call_with_simple_message_data(self.set_tilt_velocity), queue_size=100) + + if self._api.has_capability('ContinuousZoom'): + self._zoom_velocity_subscriber = rospy.Subscriber( + "control/zoom/velocity", Int32, + self._call_with_simple_message_data(self.set_zoom_velocity), queue_size=100) + + if self._api.has_capabilities('AbsolutePan', 'AbsoluteTilt', 'AbsoluteZoom'): + self._look_at_subscriber = rospy.Subscriber( + "control/look_at", PointInRectangle, self._call_with_pir_message(self.look_at), queue_size=100) + + if self._api.has_capability('AutoFocus'): + self._autofocus_subscriber = rospy.Subscriber( + "control/camera/focus/auto", Bool, self._call_with_simple_message_data(self.set_autofocus), queue_size=100) + + if self._api.has_capability('AbsoluteFocus'): + self._focus_subscriber = rospy.Subscriber( + "control/camera/focus/absolute", Int32, + self._call_with_simple_message_data(self.set_focus), queue_size=100) + + if self._api.has_capability('RelativeFocus'): + self._focus_relative_subscriber = rospy.Subscriber( + "control/camera/focus/relative", Int32, + self._call_with_simple_message_data(self.adjust_focus), queue_size=100) + + if self._api.has_capability('ContinuousFocus'): + self._focus_velocity_subscriber = rospy.Subscriber( + "control/camera/focus/velocity", Int32, + self._call_with_simple_message_data(self.set_focus_velocity), queue_size=100) + + if self._api.has_capability('AutoIris'): + self._autoiris_subscriber = rospy.Subscriber( + "control/camera/iris/auto", Bool, self._call_with_simple_message_data(self.set_autoiris), queue_size=100) + + if self._api.has_capability('AbsoluteIris'): + self._iris_subscriber = rospy.Subscriber( + "control/camera/iris/absolute", Int32, + self._call_with_simple_message_data(self.set_iris), queue_size=100) + + if self._api.has_capability('RelativeIris'): + self._iris_relative_subscriber = rospy.Subscriber( + "control/camera/iris/relative", Int32, + self._call_with_simple_message_data(self.adjust_iris), queue_size=100) + + if self._api.has_capability('ContinuousIris'): + self._iris_velocity_subscriber = rospy.Subscriber( + "control/camera/iris/velocity", Int32, + self._call_with_simple_message_data(self.set_iris_velocity), queue_size=100) + + if self._api.has_capability('AbsoluteBrightness'): + self._brightness_subscriber = rospy.Subscriber( + "control/camera/brightness/absolute", Int32, + self._call_with_simple_message_data(self.set_brightness), queue_size=100) + + if self._api.has_capability('RelativeBrightness'): + self._brightness_relative_subscriber = rospy.Subscriber( + "control/camera/brightness/relative", Int32, + self._call_with_simple_message_data(self.adjust_brightness), queue_size=100) + + if self._api.has_capability('ContinuousBrightness'): + self._brightness_velocity_subscriber = rospy.Subscriber( + "control/camera/brightness/velocity", Int32, + self._call_with_simple_message_data(self.set_brightness_velocity), queue_size=100) + + if self._api.has_capability('BackLight'): + self._use_backlight_subscriber = rospy.Subscriber( + "control/camera/backlight_compensation", Bool, + self._call_with_simple_message_data(self.use_backlight_compensation), queue_size=100) + + if self._api.has_capabilities('IrCutFilter', 'AutoIrCutFilter'): + self._use_ir_cut_filter_auto_subscriber = rospy.Subscriber( + "control/camera/ir_cut_filter/auto", Bool, + self._call_with_simple_message_data(self.set_ir_cut_filter_auto), queue_size=100) + + if self._api.has_capabilities('IrCutFilter'): + self._use_ir_cut_filter_use_subscriber = rospy.Subscriber( + "control/camera/ir_cut_filter/use", Bool, + self._call_with_simple_message_data(self.set_ir_cut_filter_use), queue_size=100) + + def set_ptz(self, pan, tilt, zoom): + """Command the PTZ unit with an absolute pose taking into account flips and mirroring. + + :param pan: The desired pan. In None, pan is not commanded at all. + The value is automatically normalized to <-180,+180> + :type pan: float + :param tilt: The desired tilt. In None, tilt is not commanded at all. + The value is automatically normalized to <-180,+180> + :type tilt: float + :param zoom: The desired zoom level. In None, zoom is not commanded at all. + :type pan: int + :return: The pan, tilt and zoom values that were really applied (e.g. the cropped and normalized input) + :rtype: tuple + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + from -170 to +170 pan is requested). + + .. note:: Since the pan and tilt values are periodic and normalization takes place in this function, you can + simply call this command in loops like e.g. ``for pan in range(0,3600,30): move_ptz_absolute(pan)`` + to rotate the camera 10 times. + """ + (pan, tilt) = self._apply_flip_and_mirror_absolute(pan, tilt) + return self._api.move_ptz_absolute(pan, tilt, zoom) + + def adjust_ptz(self, pan, tilt, zoom): + """Command the PTZ unit with a relative pose shift taking into account flips and mirroring. + + :param pan: The pan change. In None or 0, pan remains unchanged. + The value is automatically normalized to <-360,+360>. May be negative. + :type pan: float + :param tilt: The tilt change. In None or 0, tilt remains unchanged. + The value is automatically normalized to <-360,+360>. May be negative. + :type tilt: float + :param zoom: The zoom change. In None or 0, zoom remains unchanged. May be negative. + :type pan: int + :return: The pan, tilt and zoom change values that were really applied (e.g. the cropped and normalized input) + :rtype: tuple + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + by 300 deg pan is requested). + """ + (pan, tilt) = self._apply_flip_and_mirror_relative(pan, tilt) + return self._api.move_ptz_relative(pan, tilt, zoom) + + def set_ptz_velocity(self, pan, tilt, zoom): + """Command the PTZ unit velocity in terms of pan, tilt and zoom taking into account flips and mirroring. + + :param pan: Pan speed. In None or 0, pan remains unchanged. Pan speed is aperiodic (can be higher than 360). + May be negative. + :type pan: int + :param tilt: Tilt speed. In None or 0, tilt remains unchanged. Tilt speed is aperiodic (can be higher than 360). + May be negative. + :type tilt: int + :param zoom: Zoom speed. In None or 0, zoom remains unchanged. May be negative. + :type pan: int + :return: The pan, tilt and zoom change values that were really applied (e.g. the cropped and normalized input) + :rtype: tuple + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution. + + .. note:: It is not clearly stated in the API, but practically any following absolute/relative pose command + sets velocity to zero. + """ + (pan, tilt) = self._apply_flip_and_mirror_velocity(pan, tilt) + return self._api.set_ptz_velocity(pan, tilt, zoom) + + def set_pan_tilt(self, pan, tilt): + """Command the PTZ unit with an absolute pan and tilt taking into account flips and mirroring. + + :param pan: The desired pan. In None, pan is not commanded at all. + The value is automatically normalized to <-180,+180> + :type pan: float + :param tilt: The desired tilt. In None, tilt is not commanded at all. + The value is automatically normalized to <-180,+180> + :type tilt: float + :return: The pan and tilt values that were really applied (e.g. the cropped and normalized input) + :rtype: tuple + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + from -170 to +170 pan is requested). + + .. note:: Since the pan and tilt values are periodic and normalization takes place in this function, you can + simply call this command in loops like e.g. ``for pan in range(0,3600,30): move_ptz_absolute(pan)`` + to rotate the camera 10 times. + """ + (pan, tilt) = self._apply_flip_and_mirror_absolute(pan, tilt) + return self._api.move_ptz_absolute(pan=pan, tilt=tilt)[slice(0, 2)] + + def adjust_pan_tilt(self, pan, tilt): + """Command the PTZ unit with a relative pan and tilt taking into account flips and mirroring. + + :param pan: The pan change. In None or 0, pan remains unchanged. + The value is automatically normalized to <-360,+360>. May be negative. + :type pan: float + :param tilt: The tilt change. In None or 0, tilt remains unchanged. + The value is automatically normalized to <-360,+360>. May be negative. + :type tilt: float + :return: The pan and tilt change values that were really applied (e.g. the cropped and normalized input) + :rtype: tuple + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + by 300 deg pan is requested). + """ + (pan, tilt) = self._apply_flip_and_mirror_relative(pan, tilt) + return self._api.move_ptz_relative(pan=pan, tilt=tilt)[slice(0, 2)] + + def set_pan_tilt_velocity(self, pan, tilt): + """Command the PTZ unit velocity in terms of pan, tilt and zoom taking into account flips and mirroring. + + :param pan: Pan speed. In None or 0, pan remains unchanged. Pan speed is aperiodic (can be higher than 360). + May be negative. + :type pan: int + :param tilt: Tilt speed. In None or 0, tilt remains unchanged. Tilt speed is aperiodic (can be higher than 360). + May be negative. + :type tilt: int + :return: The pan and tilt velocity values that were really applied (e.g. the cropped and normalized input) + :rtype: tuple + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution. + + .. note:: It is not clearly stated in the API, but practically any following absolute/relative pose command + sets velocity to zero. + """ + (pan, tilt) = self._apply_flip_and_mirror_velocity(pan, tilt) + return self._api.set_ptz_velocity(pan=pan, tilt=tilt)[slice(0, 2)] + + def set_pan(self, pan): + """Command an absolute pan taking into account flips and mirroring. + + :param pan: The desired pan. The value is automatically normalized to <-180,+180> + :type pan: float + :return: The pan value that was really applied (e.g. the cropped and normalized input) + :rtype: float + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + from -170 to +170 pan is requested). + + .. note:: Since the pan and tilt values are periodic and normalization takes place in this function, you can + simply call this command in loops like e.g. ``for pan in range(0,3600,30): move_ptz_absolute(pan)`` + to rotate the camera 10 times. + """ + (pan, tilt) = self._apply_flip_and_mirror_absolute(pan, 0) + return self._api.move_ptz_absolute(pan=pan)[0] + + def set_tilt(self, tilt): + """Command an absolute tilt taking into account flips and mirroring. + + :param tilt: The desired tilt. The value is automatically normalized to <-180,+180> + :type tilt: float + :return: The tilt value that was really applied (e.g. the cropped and normalized input) + :rtype: float + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + from -170 to +170 pan is requested). + + .. note:: Since the pan and tilt values are periodic and normalization takes place in this function, you can + simply call this command in loops like e.g. ``for pan in range(0,3600,30): move_ptz_absolute(pan)`` + to rotate the camera 10 times. + """ + (pan, tilt) = self._apply_flip_and_mirror_absolute(0, tilt) + return self._api.move_ptz_absolute(tilt=tilt)[1] + + def set_zoom(self, zoom): + """Command an absolute zoom. + + :param zoom: The desired zoom level. + :type zoom: int + :return: The zoom value that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + from -170 to +170 pan is requested). + + .. note:: Since the pan and tilt values are periodic and normalization takes place in this function, you can + simply call this command in loops like e.g. ``for pan in range(0,3600,30): move_ptz_absolute(pan)`` + to rotate the camera 10 times. + """ + return self._api.move_ptz_absolute(zoom=zoom)[2] + + def adjust_pan(self, pan): + """Command a relative pan taking into account flips and mirroring. + + :param pan: The pan change. The value is automatically normalized to <-360,+360>. May be negative. + :type pan: float + :return: The pan change value that was really applied (e.g. the cropped and normalized input) + :rtype: float + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + by 300 deg pan is requested). + """ + (pan, _) = self._apply_flip_and_mirror_relative(pan, 0) + return self._api.move_ptz_relative(pan=pan)[0] + + def adjust_tilt(self, tilt): + """Command a relative tilt taking into account flips and mirroring. + + :param tilt: The tilt change. The value is automatically normalized to <-360,+360>. May be negative. + :type tilt: float + :return: The tilt change value that was really applied (e.g. the cropped and normalized input) + :rtype: float + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + by 300 deg pan is requested). + """ + (_, tilt) = self._apply_flip_and_mirror_relative(0, tilt) + return self._api.move_ptz_relative(tilt=tilt)[1] + + def adjust_zoom(self, zoom): + """Command a relative zoom. + + :param zoom: The zoom change. In None or 0, zoom remains unchanged. May be negative. + :type zoom: int + :return: The zoom change value that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + by 300 deg pan is requested). + """ + return self._api.move_ptz_relative(zoom=zoom)[2] + + def set_pan_velocity(self, pan): + """Command pan velocity. + + :param pan: Pan speed. Pan speed is aperiodic (can be higher than 360). May be negative. + :type pan: int + :return: The pan velocity that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution. + + .. note:: It is not clearly stated in the API, but practically any following absolute/relative pose command + sets velocity to zero. + """ + (pan, _) = self._apply_flip_and_mirror_velocity(pan, 0) + return self._api.set_ptz_velocity(pan=pan)[0] + + def set_tilt_velocity(self, tilt): + """Command tilt velocity. + + :param tilt: Tilt speed. Tilt speed is aperiodic (can be higher than 360). May be negative. + :type tilt: int + :return: The tilt velocity that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution. + + .. note:: It is not clearly stated in the API, but practically any following absolute/relative pose command + sets velocity to zero. + """ + (_, tilt) = self._apply_flip_and_mirror_velocity(0, tilt) + return self._api.set_ptz_velocity(tilt=tilt)[1] + + def set_zoom_velocity(self, zoom): + """Command zoom velocity. + + :param zoom: Zoom speed. May be negative. + :type zoom: int + :return: The zoom velocity that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution. + + .. note:: It is not clearly stated in the API, but practically any following absolute/relative pose command + sets velocity to zero. + """ + return self._api.set_ptz_velocity(zoom=zoom)[2] + + def look_at(self, x, y, image_width, image_height): + """Point the camera center to a point with the given coordinates in the camera image. + + :param x: X coordinate of the look-at point. + :type x: int + :param y: X coordinate of the look-at point. + :type y: int + :param image_width: Width of the image in pixels. + :type image_width: int + :param image_height: Height of the image in pixels. + :type image_height: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + self._api.look_at(x, y, image_width, image_height) + + def set_autofocus(self, use): + """Command the camera to use/stop using autofocus. + + :param use: True: use autofocus; False: do not use it. + :type use: bool + :return: use + :rtype: :py:class:`bool` + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + self._api.use_autofocus(use) + self._autofocus = use + self._send_parameter_update("autofocus", use) + return use + + def set_focus(self, focus, set_also_autofocus=True): + """Set focus to the desired value (implies turning off autofocus). + + :param focus: The desired focus value. + :type focus: int + :param set_also_autofocus: If True and autofocus is on, turn it off first. + :type set_also_autofocus: bool + :return: The focus value that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + focus = self._api.set_focus(focus) + self._focus = focus + self._send_parameter_update("focus", focus) + if set_also_autofocus: + self._autofocus = False + self._send_parameter_update("autofocus", False) + return focus + + def adjust_focus(self, amount, set_also_autofocus=True): + """Add the desired amount to the focus value (implies turning off autofocus). + + :param amount: The desired focus change amount. + :type amount: int + :param set_also_autofocus: If True and autofocus is on, turn it off first. + :type set_also_autofocus: bool + :return: The focus change amount that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + amount = self._api.adjust_focus(amount) + self._focus += amount + self._send_parameter_update("focus", self._focus) + if set_also_autofocus: + self._autofocus = False + self._send_parameter_update("autofocus", False) + return amount + + def set_focus_velocity(self, velocity): + """Set the focus "speed" (implies turning off autofocus). + + :param velocity: The desired focus velocity. + :type velocity: int + :return: The focus velocity that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + return self._api.set_focus_velocity(velocity) + # TODO self.focus updating + + def set_autoiris(self, use): + """Command the camera to use/stop using auto iris adjustment. + + :param use: True: use auto iris adjustment; False: do not use it. + :type use: bool + :return: use + :rtype: :py:class:`bool` + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + self._api.use_autoiris(use) + self._autoiris = use + self._send_parameter_update("autoiris", use) + return use + + def set_iris(self, iris, set_also_autoiris=True): + """Set iris to the desired value (implies turning off autoiris). + + :param iris: The desired iris value. + :type iris: int + :param set_also_autoiris: If True and autoiris is on, turn it off first. + :type set_also_autoiris: bool + :return: The iris value that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + iris = self._api.set_iris(iris) + self._iris = iris + self._send_parameter_update("iris", iris) + if set_also_autoiris: + self._autoiris = False + self._send_parameter_update("autoiris", False) + return iris + + def adjust_iris(self, amount, set_also_autoiris=True): + """Add the desired amount to the iris value (implies turning off autoiris). + + :param amount: The desired iris change amount. + :type amount: int + :param set_also_autoiris: If True and autoiris is on, turn it off first. + :type set_also_autoiris: bool + :return: The iris change amount that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + amount = self._api.adjust_iris(amount) + self._iris += amount + self._send_parameter_update("iris", self._iris) + if set_also_autoiris: + self._autoiris = False + self._send_parameter_update("autoiris", False) + return amount + + def set_iris_velocity(self, velocity): + """Set the iris "speed" (implies turning off autoiris). + + :param velocity: The desired iris velocity. + :type velocity: int + :return: The iris velocity that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + return self._api.set_iris_velocity(velocity) + # TODO self.iris updating + + def set_brightness(self, brightness): + """Set brightness to the desired value. + + :param brightness: The desired brightness value. + :type brightness: int + :return: The brightness value that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: The brightness setting has no effect on Axis 214 PTZ. + """ + brightness = self._api.set_brightness(brightness) + self._brightness = brightness + self._send_parameter_update("brightness", brightness) + return brightness + + def adjust_brightness(self, amount): + """Add the desired amount to the brightness value. + + :param amount: The desired brightness change amount. + :type amount: int + :return: The brightness change amount that was really applied (e.g. the cropped and normalized input) + :rtype: int + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: The brightness setting has no effect on Axis 214 PTZ. + """ + amount = self._api.adjust_brightness(amount) + self._brightness += amount + self._send_parameter_update("brightness", self._brightness) + return amount + + def set_brightness_velocity(self, velocity): + """Set the brightness "speed". + + :param velocity: The desired brightness velocity. + :type velocity: int + :return: The brightness velocity that was really applied (e.g. the cropped and normalized input) + :rtype: :py:class:`int` + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + + .. note:: The brightness setting has no effect on Axis 214 PTZ. + """ + return self._api.set_brightness_velocity(velocity) + # TODO self.brightness updating + + def use_backlight_compensation(self, use): + """Command the camera to use/stop using backlight compensation (requires autoiris=on set before). + + :param use: True: use backlight compensation; False: do not use it. + :type use: bool + :return: use + :rtype: :py:class:`bool` + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + if self._autoiris: # the compensation needs autoiris to be active + self._api.use_backlight_compensation(use) + self._backlight = use + else: + use = False + + self._send_parameter_update("backlight", use) + + return use + + def set_ir_cut_filter_auto(self, use): + """Command the camera to use auto infrared filter (requires autoiris=on set before). + + :param use: True: use automatic infrared filter; + False: use always. + :type use: bool + :return: True if the filter is always used, None if it is set to auto. + :rtype: :py:class:`bool` + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + use = (None if use else True) + # auto IR filter requires autoiris to be active + if self._autoiris or use is not None: + self._api.use_ir_cut_filter(use) + self._ir_cut_filter = use + else: + use = True + + self._send_parameter_update("ircutfilter", "auto" if (use is None) else "on") + + return use + + def set_ir_cut_filter_use(self, use): + """Command the camera to use/stop using infrared filter. + + :param use: Whether to use the filter. + :type use: bool + :return: use + :rtype: :py:class:`bool` + + :raises: :py:class:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:class:`IOError`, :py:class:`urllib2.URLError` on network communication error + """ + self._api.use_ir_cut_filter(use) + self._ir_cut_filter = use + + self._send_parameter_update("ircutfilter", "on" if use else "off") + + return use + + def _reconfigure(self, config, level, subname): + """Dynamic reconfigure callback. + + :param config: The config to be used. + :type config: dict + :return: The config with really used values. + :rtype: dict + """ + if self._executing_reconfigure or self._executing_parameter_update or self._axis._executing_reconfigure: + return config + + with self._reconfigure_mutex: + self._executing_reconfigure = True + + try: + if config.autofocus != self._autofocus: + if self._api.has_capability('AutoFocus'): + self.set_autofocus(config.autofocus) + else: + rospy.loginfo("Camera on host %s doesn't support autofocus." % self._api.hostname) + except (IOError, ValueError, RuntimeError) as e: + rospy.logwarn("Could not apply dynamic reconfigure for autofocus. Cause: %r" % e) + + try: + if config.focus != self._focus: + if self._api.has_capability('AbsoluteFocus'): + self.set_focus(config.focus) + else: + rospy.loginfo("Camera on host %s doesn't support absolute focus control." % self._api.hostname) + + except (IOError, ValueError, RuntimeError) as e: + rospy.logwarn("Could not apply dynamic reconfigure for focus. Cause: %r" % e) + + try: + if config.autoiris != self._autoiris: + if self._api.has_capability('AutoIris'): + self.set_autoiris(config.autoiris) + else: + rospy.loginfo("Camera on host %s doesn't support autoiris." % self._api.hostname) + + except (IOError, ValueError, RuntimeError) as e: + rospy.logwarn("Could not apply dynamic reconfigure for autoiris. Cause: %r" % e) + + try: + if config.iris != self._iris: + if self._api.has_capability('AbsoluteIris'): + self.set_iris(config.iris) + else: + rospy.loginfo("Camera on host %s doesn't support absolute iris control." % self._api.hostname) + + except (IOError, ValueError, RuntimeError) as e: + rospy.logwarn("Could not apply dynamic reconfigure for iris. Cause: %r" % e) + + try: + if config.brightness != self._brightness: + # there is no capability for brightness + self.set_brightness(config.brightness) + except (IOError, ValueError, RuntimeError) as e: + rospy.logwarn("Could not apply dynamic reconfigure for brightness. Cause: %r" % e) + + try: + if config.backlight != self._backlight: + if self._api.has_capability('BackLight'): + self.use_backlight_compensation(config.backlight) + else: + rospy.loginfo("Camera on host %s doesn't support backlight compensation." % self._api.hostname) + + except (IOError, ValueError, RuntimeError) as e: + rospy.logwarn("Could not apply dynamic reconfigure for backlight compenstaion. Cause: %r" % e) + + try: + ir = None if config.ircutfilter == "auto" else (config.ircutfilter == "on") + if ir != self._ir_cut_filter: + if self._api.has_capability('IrCutFilter'): + if ir is None or self._ir_cut_filter is None: + self.set_ir_cut_filter_auto(ir is None) + if ir is not None: + self.set_ir_cut_filter_use(ir) + else: + rospy.loginfo("Camera on host %s doesn't support IR cut filter control." % self._api.hostname) + + except (IOError, ValueError, RuntimeError) as e: + rospy.logwarn("Could not apply dynamic reconfigure for IR cut filter. Cause: %r" % e) + + config.autofocus = self._autofocus + config.focus = self._focus + config.autoiris = self._autoiris + config.iris = self._iris + config.brightness = self._brightness + config.backlight = self._backlight + config.ircutfilter = ("auto" if self._ir_cut_filter is None else ("on" if self._ir_cut_filter else "off")) + + self._executing_reconfigure = False + + return config + + # Helper functions + + def _send_parameter_update(self, parameter, value): + """Notify the parameter change via dynamic reconfigure. + + :param parameter: The parameter that has changed. + :type parameter: basestring + :param value: New value of the parameter. + :type value: Any + """ + if self._executing_parameter_update: + return + + with self._parameter_update_mutex: + update = dict() + update[parameter] = value + + self._executing_parameter_update = True + + if hasattr(self._axis, 'srv') and self._axis.srv is not None and not self._axis._executing_reconfigure: + # axis.srv is instantiated after camera controller + self._axis.srv.update_configuration(update) + + if hasattr(self, '_dynamic_reconfigure_server') and self._dynamic_reconfigure_server is not None \ + and not self._executing_reconfigure: + # this server can also be initialized later + self._dynamic_reconfigure_server.update_configuration(update) + + self._executing_parameter_update = False + + def _apply_flip_and_mirror_absolute(self, pan, tilt): + """Apply flipping and mirroring to absolute pan and tilt command. + + :param pan: The input pan. + :type pan: float + :param tilt: The input tilt. + :type tilt: float + :return: The corrected pan and tilt. + :rtype: tuple + """ + if self._flip_vertically: + tilt = -tilt + if self._flip_horizontally: + pan = 180 - pan + if self._mirror_horizontally: + pan = -pan + + return pan, tilt + + def _apply_flip_and_mirror_relative(self, pan, tilt): + """Apply flipping and mirroring to relative pan and tilt command. + + :param pan: The input pan. + :type pan: float + :param tilt: The input tilt. + :type tilt: float + :return: The corrected pan and tilt. + :rtype: tuple + """ + if self._flip_vertically: + tilt = -tilt + if self._flip_horizontally: + pan = -pan + if self._mirror_horizontally: + pan = -pan + + return pan, tilt + + def _apply_flip_and_mirror_velocity(self, pan, tilt): + """Apply flipping and mirroring to velocity pan and tilt command. + + :param pan: The input pan. + :type pan: float + :param tilt: The input tilt. + :type tilt: float + :return: The corrected pan and tilt. + :rtype: tuple + """ + if self._flip_vertically: + tilt = -tilt + if self._flip_horizontally: + pan = -pan + if self._mirror_horizontally: + pan = -pan + + return pan, tilt + + def _record_diagnostics(self, func): + """Wrap a function call and record diagnostics about if it has thrown an exception or not. + + :param func: The function to be wrapped. + :type func: function + :return: The wrapped function. + :rtype: function + """ + def new_func(msg): + try: + func(msg) + self._last_command_error = None + except Exception, e: + self._last_command_error = e + raise e + + return new_func + + def _call_with_simple_message_data(self, func): + """Create a one-arg lambda that extracts the "data" field from its argument and passes it to the given function. + + :param func: The function to call. + :type func: function + :return: The lambda function. + :rtype: function + """ + return self._record_diagnostics(lambda (msg): func(msg.data)) + + def _call_with_ptz_message(self, func): + """ + Create a one-arg lambda that extracts the "pan", "tilt" and "zoom" fields from its argument and passes them to + the given function. + + :param func: The function to call. + :type func: function + :return: The lambda function. + :rtype: function + """ + return self._record_diagnostics(lambda (msg): func(msg.pan, msg.tilt, msg.zoom)) + + def _call_with_pt_message(self, func): + """ + Create a one-arg lambda that extracts the "pan" and "tilt" fields from its argument and passes them to the given + function. + + :param func: The function to call. + :type func: function + :return: The lambda function. + :rtype: function + """ + return self._record_diagnostics(lambda (msg): func(msg.pan, msg.tilt)) + + def _call_with_pir_message(self, func): + """ + Create a one-arg lambda that extracts the "x", "y", "width" and "height" fields from its argument and passes + them to the given function. + + :param func: The function to call. + :type func: function + :return: The lambda function. + :rtype: function + """ + return self._record_diagnostics(lambda (msg): func(msg.x, msg.y, msg.image_width, msg.image_height)) + + def _diagnostic_last_command(self, message): + """Fill in the diagnostics message about last command success. + + :param message: The message to be filled. + :type message: DiagnosticStatusWrapper + :return: The altered message. + :rtype: DiagnosticStatusWrapper + """ + assert isinstance(message, DiagnosticStatusWrapper) + if self._last_command_error is None: + message.summary(DiagnosticStatusWrapper.OK, "Last command succeeded") + else: + message.summary(DiagnosticStatusWrapper.ERROR, "Last command failed: %s" % str(self._last_command_error)) diff --git a/scripts/axis_camera/dynamic_reconfigure_server2.py b/scripts/axis_camera/dynamic_reconfigure_server2.py new file mode 100644 index 0000000..344e0d5 --- /dev/null +++ b/scripts/axis_camera/dynamic_reconfigure_server2.py @@ -0,0 +1,156 @@ +# Software License Agreement (BSD License) +# +# Copyright (c) 2009, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +""" +Python client API for dynamic_reconfigure (L{DynamicReconfigureClient}) as well as +example server implementation (L{DynamicReconfigureServer}). +""" + +# This is an enhanced version of +# driver_common/dynamic_reconfigure/src/dynamic_reconfigure/server.py +# to support the "subname" parameter. +# Downloaded and updated from https://gist.github.com/astraw/1059742 + +from __future__ import with_statement + +try: + import roslib; + roslib.load_manifest('dynamic_reconfigure') +except: + pass +import rospy +import rosservice +import threading +import time +import copy +from dynamic_reconfigure import DynamicReconfigureCallbackException +from dynamic_reconfigure.srv import Reconfigure as ReconfigureSrv +from dynamic_reconfigure.msg import Config as ConfigMsg +from dynamic_reconfigure.msg import ConfigDescription as ConfigDescrMsg +from dynamic_reconfigure.msg import IntParameter, BoolParameter, StrParameter, DoubleParameter, ParamDescription +from dynamic_reconfigure.encoding import * + + +class Server(object): + def __init__(self, type, callback, subname=None): + """Create the dynamic reconfigure server. + + :param type: Type of the server. + :type type: any + :param callback: Reconfigure callback. + :type callback: func + :param subname: The "subname" of the server. It will be appended to the name an unmodified dynamic reconfigure + server would have. + :type subname: :py:obj:`basestring` + """ + self.mutex = threading.Lock() + self.type = type + self.config = type.defaults.copy() + + self.subname = subname + if subname is None: + self._prefix = "~" + else: + self._prefix = subname + "/" + + self.description = encode_description(type) + self._copy_from_parameter_server() + self.callback = callback + self._clamp(self.config) + + # setup group defaults + self.config['groups'] = get_tree(self.description) + self.config = initial_config(encode_config(self.config), type.config_description) + + self.descr_topic = rospy.Publisher('%sparameter_descriptions' % self._prefix, ConfigDescrMsg, latch=True, queue_size=10) + self.descr_topic.publish(self.description); + + self.update_topic = rospy.Publisher('%sparameter_updates' % self._prefix, ConfigMsg, latch=True, queue_size=10) + self._change_config(self.config, type.all_level) + + self.set_service = rospy.Service('%sset_parameters' % self._prefix, ReconfigureSrv, self._set_callback) + + def update_configuration(self, changes): + with self.mutex: + new_config = copy.deepcopy(self.config) + new_config.update(changes) + self._clamp(new_config) + return self._change_config(new_config, self._calc_level(new_config, self.config)) + + def _copy_from_parameter_server(self): + for param in extract_params(self.type.config_description): + try: + self.config[param['name']] = rospy.get_param(self._prefix + param['name']) + except KeyError: + pass + + def _copy_to_parameter_server(self): + for param in extract_params(self.type.config_description): + rospy.set_param(self._prefix + param['name'], self.config[param['name']]) + + def _change_config(self, config, level): + if self.subname is not None and self.subname != '': + self.config = self.callback(config, level, subname=self.subname) + else: + self.config = self.callback(config, level) + + if self.config is None: + msg = 'Reconfigure callback should return a possibly updated configuration.' + rospy.logerr(msg) + raise DynamicReconfigureCallbackException(msg) + + self._copy_to_parameter_server() + + self.update_topic.publish(encode_config(self.config)) + + return self.config + + def _calc_level(self, config1, config2): + level = 0 + for param in extract_params(self.type.config_description): + if config1[param['name']] != config2[param['name']]: + level |= param['level'] + + return level + + def _clamp(self, config): + for param in extract_params(self.type.config_description): + maxval = self.type.max[param['name']] + minval = self.type.min[param['name']] + val = config[param['name']] + if val > maxval and maxval != "": + config[param['name']] = maxval + elif val < minval and minval != "": + config[param['name']] = minval + + def _set_callback(self, req): + return encode_config(self.update_configuration(decode_config(req.config, self.type.config_description))) diff --git a/scripts/axis_camera/dynamic_reconfigure_tools.py b/scripts/axis_camera/dynamic_reconfigure_tools.py new file mode 100644 index 0000000..5711d9c --- /dev/null +++ b/scripts/axis_camera/dynamic_reconfigure_tools.py @@ -0,0 +1,57 @@ +def change_enum_items(type, parameter_name, new_items, default=None): + """ + Take an enum-typed parameter in the given autogenerated cfg type and reset its possible values to new_items. + + You can then start a dynamic_reconfigure server which advertises the changed enum domain. + To achieve this, you need to call this function before creating the server. + + .. note:: This is a rather simple script, it e.g. ignores parameter groups. + + :param type type: One of the autogenerated config types (package.cfg.*Config). + :param basestring parameter_name: Name of the enum parameter to change. + :param new_items: The items that will form the new domain of the enum. + :type new_items: array of {'name': ..., 'value': ..., 'description': ...} + :param any default: If provided, this value is used as the default. If not, the first value in new_items is used. + + :raises RuntimeError: If there is no valid enum parameter with the given name in the given type. + """ + + if not hasattr(type, 'config_description') or not hasattr(type, 'defaults'): + raise RuntimeError('Type %s is not a valid dynamic reconfigure type.' % str(type)) + + for param_desc in type.config_description['parameters']: + if param_desc['name'] == parameter_name: + if param_desc['edit_method'] == '': + raise RuntimeError('Type %s has empty edit_method, which means it is not a proper enum.' % str(type)) + + edit_method = eval(param_desc['edit_method']) + enum = edit_method['enum'] + + if len(enum) == 0: + raise RuntimeError('Type %s edit_method has empty enum, which means it is not a proper enum.' % + str(type)) + + # we will copy all "unnecesarry" info (line number, filename etc.) from the first item + sample_item = enum[0] + + new_enum = [] + for item in new_items: + new_item = sample_item.copy() + new_item['name'] = item['name'] + new_item['value'] = item['value'] + new_item['description'] = item['description'] + new_enum.append(new_item) + + edit_method['enum'] = new_enum + param_desc['edit_method'] = repr(edit_method) + + # if no default value was explicitly specified, use the first value + if default is None: + default = new_enum[0]['value'] + + param_desc['default'] = default + type.defaults[param_desc['name']] = default + + return + + raise RuntimeError('Parameter "%s" not found.' % parameter_name) \ No newline at end of file diff --git a/scripts/axis_camera/position_streaming.py b/scripts/axis_camera/position_streaming.py new file mode 100644 index 0000000..5ac2d04 --- /dev/null +++ b/scripts/axis_camera/position_streaming.py @@ -0,0 +1,201 @@ +import threading +from math import radians + +import rospy +from sensor_msgs.msg import JointState +from dynamic_reconfigure.msg import Config, IntParameter, DoubleParameter +from diagnostic_updater import Updater, DiagnosedPublisher, TimeStampStatusParam, FrequencyStatusParam + +from axis_camera.msg import Axis, PTZ + + +class PositionStreamingThread(threading.Thread): + """ + This class handles publication of the positional state of the camera to a ROS message and to joint_states + (and using robot_state_publisher also to TF). + + The thread doesn't support pausing, because it doesn't make sense if we want TF data. + """ + + def __init__(self, axis, api): + """Create the thread. + + :param axis: The parameter source. + :type axis: :py:class:`AxisPTZ` + :param api: The VAPIX API instance that allows the thread to access positional data. + :type api: :py:class:`VAPIX` + """ + threading.Thread.__init__(self) + + self.axis = axis + self.api = api + + # Permit program to exit even if threads are still running by flagging + # thread as a daemon: + self.daemon = True + + self._diagnostic_updater = Updater() + self._diagnostic_updater.setHardwareID(api.hostname) + + # BACKWARDS COMPATIBILITY LAYER + self.cameraPosition = None # deprecated + self.msg = Axis() # deprecated + + def run(self): + """Run the thread.""" + frequency = self.axis._state_publishing_frequency + rate = rospy.Rate(frequency) + + state_publisher = DiagnosedPublisher( + rospy.Publisher("camera/ptz", PTZ, queue_size=100), + self._diagnostic_updater, FrequencyStatusParam({'min': frequency, 'max': frequency}, tolerance=0.2), TimeStampStatusParam() + ) + joint_states_publisher = DiagnosedPublisher( + rospy.Publisher("camera/joint_states", JointState, queue_size=100), + self._diagnostic_updater, FrequencyStatusParam({'min': frequency, 'max': frequency}, tolerance=0.2), TimeStampStatusParam() + ) + parameter_updates_publisher = rospy.Publisher("axis_ptz/parameter_updates", Config, queue_size=100) + + while not rospy.is_shutdown(): + # publish position forever + try: + # get camera position from API + camera_position = self.api.get_camera_position() # we use deprecated param values + message_time = rospy.Time.now() + + # Create and publish the PTZ message + message = self._create_camera_position_message(camera_position, message_time) + state_publisher.publish(message) + + # Create and publish JointState + joint_states_message = self._create_camera_joint_states_message(camera_position, message_time) + joint_states_publisher.publish(joint_states_message) + + # Publish the parameter updates (because of backwards compatibility) + parameter_updates_message = self._create_parameter_updates_message(camera_position) + parameter_updates_publisher.publish(parameter_updates_message) + + # set the parameters (because of backwards compatibility) + rospy.set_param("axis_ptz/pan", camera_position['pan']) + rospy.set_param("axis_ptz/tilt", camera_position['tilt']) + rospy.set_param("axis_ptz/zoom", camera_position['zoom']) + + # Create and publish the deprecated Axis message + self.cameraPosition = camera_position # backwards compatibility + self.publishCameraState() # backwards compatibility + except (IOError, ValueError, RuntimeError) as e: + rospy.logwarn("Could not determine current camera position. Waiting 1 s. Cause: %s" % repr(e.args)) + rospy.sleep(1) + + self._diagnostic_updater.update() + + try: + rate.sleep() + except rospy.ROSTimeMovedBackwardsException: + rospy.logwarn("Detected jump back in time.") + + def _create_camera_position_message(self, camera_position, timestamp): + """Convert the camera_position dictionary to a PTZ message. + + :param camera_position: The camera position. Should contain keys 'pan', 'tilt', and probably also 'zoom'. + :type camera_position: dict + :param timestamp: The time we relate the camera position to. + :type timestamp: :py:class:`rospy.Time` + :return: The PTZ message. + :rtype: :py:class:`axis_camera.msg.PTZ` + """ + message = PTZ() + + message.header.stamp = timestamp + message.header.frame_id = self.axis._frame_id + + message.pan = camera_position['pan'] + message.tilt = camera_position['tilt'] + if 'zoom' in camera_position: + message.zoom = camera_position['zoom'] + + if self.axis.flip: + self._correct_flipped_pan_tilt_in_message(message) + + return message + + def _create_camera_joint_states_message(self, camera_position, timestamp): + """ + Convert the camera_position dictionary to a JointState message. + :param camera_position: The camera position. Should contain keys 'pan', 'tilt', and probably also 'zoom'. + :type camera_position: dict + :param timestamp: The time we relate the camera position to. + :type timestamp: :py:class:`rospy.Time` + :return: The JointState message. + :rtype: :py:class:`sensor_msgs.msg.JointState` + """ + message = JointState() + + message.header.stamp = timestamp + message.header.frame_id = self.axis._frame_id + + message.name = ["axis_pan_j", "axis_tilt_j"] + message.position = [radians(camera_position['pan']), radians(camera_position['tilt'])] + + # TODO message.velocity??? + # TODO flipping? + + return message + + def _create_parameter_updates_message(self, camera_position): + """ + Create a parameter_updates message to update the deprecated dynamic_reconigurable pan, tilt and zoom params. + :param camera_position: The camera position. Should contain keys 'pan', 'tilt', and probably also 'zoom'. + :type camera_position: dict + :return: The Config message. + :rtype: :py:class:`axis_camera.cfg.Config` + """ + message = Config() + + message.doubles.append(DoubleParameter(name="pan", value=camera_position['pan'])) + message.doubles.append(DoubleParameter(name="tilt", value=camera_position['tilt'])) + message.ints.append(IntParameter(name="zoom", value=camera_position['zoom'])) + + return message + + @staticmethod + def _correct_flipped_pan_tilt_in_message(message): + """ + If flipping the image is required, do the flipping on a PTZ message fields. + :param message: A PTZ or Axis message. + :type message: :py:class:`axis_camera.msg.PTZ` | :py:class:`axis_camera.msg.Axis` + """ + message.pan = 180 - message.pan + if message.pan > 180: + message.pan -= 360 + elif message.pan < -180: + message.pan += 360 + message.tilt = -message.tilt + + # BACKWARDS COMPATIBILITY LAYER + + def queryCameraPosition(self): # deprecated + """Deprecated.""" + pass # is done in the run method + + def publishCameraState(self): # deprecated + """Deprecated.""" + if self.cameraPosition is not None: + self.msg.pan = float(self.cameraPosition['pan']) + if self.axis.flip: + self.adjustForFlippedOrientation() + self.msg.tilt = float(self.cameraPosition['tilt']) + self.msg.zoom = float(self.cameraPosition['zoom']) + self.msg.iris = 0.0 + if 'iris' in self.cameraPosition: + self.msg.iris = float(self.cameraPosition['iris']) + self.msg.focus = 0.0 + if 'focus' in self.cameraPosition: + self.msg.focus = float(self.cameraPosition['focus']) + if 'autofocus' in self.cameraPosition: + self.msg.autofocus = (self.cameraPosition['autofocus'] == 'on') + self.axis.pub.publish(self.msg) + + def adjustForFlippedOrientation(self): # deprecated + """Deprecated.""" + self._correct_flipped_pan_tilt_in_message(self.msg) diff --git a/scripts/axis_camera/vapix.py b/scripts/axis_camera/vapix.py new file mode 100644 index 0000000..dde6cee --- /dev/null +++ b/scripts/axis_camera/vapix.py @@ -0,0 +1,1549 @@ +"""Python 2 implementation of the VAPIX HTTP API for communicating with Axis network cameras. + +This class supports both VAPIX v2 and VAPIX v3, including autodetection of the supported API. +The VAPIX APIs are implemented based on these specifications: + +- VAPIX v2: http://www.axis.com/files/manuals/HTTP_API_VAPIX_2.pdf +- VAPIX v3: + + - streaming: http://www.axis.com/files/manuals/vapix_video_streaming_52937_en_1307.pdf + - PTZ control: http://www.axis.com/files/manuals/vapix_ptz_52933_en_1307.pdf + +When an instance of the API is obtained, the capabilities and limits of the connected camera are read automatically +and they can be queried afterwards. A :py:exc:`exceptions.RuntimeError` will be thrown when calling an API method for which the camera +doesn't have capabilities. + +:Example: + +To get an autodetected API instance allowing you to access a connected camera, use the following code: + +.. code-block:: python + + api = VAPIX.get_api_for_camera(hostname, username, password, camera_id, use_encrypted_password) + +This call throws :py:exc:`IOError` or :py:exc:`ValueError` if connection to the camera did not succeed, so keep trying in +a loop until the camera becomes reachable. + +.. note:: Tested with the following products. Tests of other products are welcome! + +- Axis 214 PTZ (firmware 4.49) with VAPIX v2 + +.. note:: Always update your camera to the newest available firmware from + http://origin-www.axis.com/ftp/pub_soft/cam_srv/ before issuing a bug. + +""" + +import urllib2 +import socket +from contextlib import closing +from abc import ABCMeta, abstractmethod + +# from rospy, we only use is_shutdown(), sleep() and logdebug/logwarn(), so if you need to use this +# API outside ROS, the transformation should be pretty easy (you could even provide a fake rospy package +# and then use this code unchanged) +import rospy + + +class Range(object): + """A helper class representing an allowed parameter range.""" + + def __init__(self, min=float('-inf'), max=float('inf'), period=None): + """Create a parameter range. + + :param min: The minimum allowed value. Minus infinity means no lower limit. + :type min: float, int + :param max: The maximum allowed value. Plus infinity means no upper limit. + :type max: float, int + :param period: If the value is periodic (e.g. angles), specify the size of the period and all values + passed to this range will first be "normalized" to the range -period/2 to period/2. + :type period: float, int + """ + self.min = min + self.max = max + self.period = period + + def _normalize(self, value): + """Adjust the value to fit inside the period if this is a periodic range. Has no effect on a-periodic ranges. + + :param value: The value to normalize. + :type value: float, int + :return: The normalized value. + :rtype: :py:class:`float`, :py:class:`int` + """ + if self.period is None: + return value + + result = value + while result > self.period/2.0: + result -= self.period + while result < -self.period / 2.0: + result += self.period + return result + + def is_in_range(self, value): + """Check if the given value satisfies this range's constraints (after being normalized). + + :param value: The value to check. + :type value: float, int + :return: If the value fits this range. + :rtype: :py:class:`bool` + """ + return self.min <= self._normalize(value) <= self.max + + def crop_value(self, value): + """If the value is outside this range, return the corresponding limit, otherwise just return the value. + + :param value: The value to crop. + :type value: float, int + :return: The cropped and normalized value. + :rtype: :py:class:`float`, :py:class:`int` + """ + value = self._normalize(value) + + if value > self.max: + return self.max + elif value < self.min: + return self.min + else: + return value + + def merge(self, range): + """Merge this range with another one (using logical AND to join the conditions). + If both ranges share the same period, it is retained. If only one of the ranges is periodic, its + period is used for the resulting range. If both ranges are periodic with different period, a :class:ValueError + is thrown. + + :param range: The range to merge with. + :type range: :py:class:`Range` + :return: A new range satisfying the limits of both this and the given range. + :rtype: :py:class:`Range` + :raises: :py:exc:`ValueError` if both ranges are periodic, and their periods differ + """ + assert isinstance(range, Range) + + period = None + if self.period is not None: + if range.period is not None: + if self.period != range.period: + raise ValueError("Cannot join two ranges with different periods.") + period = self.period + else: + period = self.period + elif range.period is not None: + period = range.period + + return Range(max(range.min, self.min), min(range.max, self.max), period) + + def __str__(self): + result = "<%f, %f>" % (self.min, self.max) + if self.period is not None: + result += " + k*%f" % self.period + return result + + def __repr__(self): + return "Range(min=%r, max=%r, period=%r)" % (self.min, self.max, self.period) + + +class PTZLimit(object): + """A helper class holding information about absolute, relative and velocity parameter ranges. + + This is useful for representing the pan, tilt or zoom parameter limits. + """ + + def __init__(self, absolute=None, relative=None, velocity=None): + """Create a limit for absolute, relative and velocity parameters. + + :param absolute: The allowed range for absolute movement. + :type absolute: :py:class:`Range` + :param relative: The allowed range for relative movement. + :type relative: :py:class:`Range` + :param velocity: The allowed range for velocity. + :type velocity: :py:class:`Range` + """ + self.absolute = absolute if absolute is not None else Range() + self.relative = relative if relative is not None else Range() + self.velocity = velocity if velocity is not None else Range() + + def merge(self, limit): + """Merge this limit with another one. + + :param limit: The limit to merge with. + :type limit: :py:class:`PTZLimit` + :return: A new limit satisfying the conditions of this and the given one. + :rtype: :py:class:`PTZLimit` + """ + assert isinstance(limit, PTZLimit) + + return PTZLimit( + self.absolute.merge(limit.absolute), + self.relative.merge(limit.relative), + self.velocity.merge(limit.velocity) + ) + + def __str__(self): + return "[absolute=%s, relative=%s, velocity=%s]" % (str(self.absolute), str(self.relative), str(self.velocity)) + + def __repr__(self): + return "PTZLimit(absolute=%r, relative=%r, velocity=%r)" % (self.absolute, self.relative, self.velocity) + + +class VAPIX(object): + """Implementation of the VAPIX HTTP API of Axis network cameras. + + This is an abstract common ancestor for both API v2 and v3, since they share the most of the functionality. + The differences between v2 and v3 are specified by overriding this class' methods in a subclass. + """ + __metaclass__ = ABCMeta + + _using_authentication = False + """Specifies whether the last get_get_api_for_camera call was using authentication credentials or they were empty""" + + def __init__(self, hostname, camera_id=1, connection_timeout=5): + """An instance of the VAPIX API. + + :param hostname: Hostname or IP address string of the connected camera. + :type hostname: basestring + :param camera_id: Id of the camera to connect to (if more video sources are available). Usually a number 1-4. + :type camera_id: int + :param connection_timeout: Timeout of API requests (in seconds). + :type connection_timeout: int + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on connection error + """ + self.hostname = hostname + self.camera_id = camera_id + self.connection_timeout = connection_timeout + + self._has_ptz = self.has_ptz() + if self._has_ptz: + self._ptz_capabilities = self._get_ptz_capabilities() + self.ptz_limits = self._get_ptz_limits() + + @abstractmethod + def _form_parameter_url(self, group): + """Construct a URL for querying the specified parameter group. + + :param group: The parameter group to get using the generated URL. Can be both a group and a single parameter. + :type group: basestring + :return: The full API URL to query. + :rtype: :py:obj:`basestring` + """ + pass + + @abstractmethod + def _form_imagesize_url(self): + """Construct a URL for querying the imagesize.cgi script. + + :return: The full API URL to query. + :rtype: :py:obj:`basestring` + """ + pass + + def get_video_stream(self, fps=24, resolution_name='CIF', compression=0, use_color=True, use_square_pixels=False): + """Return a stream connected to the camera's MJPG video source. + + :param fps: The desired frames per second. + :type fps: int + :param resolution_name: The CIF standard name of the requested stream resolution (e.g. 4CIF, 2CIFEXP, CIF). + :type resolution_name: basestring + :param compression: Compression of the image (0 - no compression, 100 - max compression). + :type compression: int + :param use_color: If True, send a color stream, otherwise send only grayscale image. + :type use_color: bool + :param use_square_pixels: If True, the resolution will be stretched to match 1:1 pixels. + By default, the pixels have a ratio of 11:12. + :return: A handle to the open stream. + :rtype: :py:class:`urllib.addinfourl` (a :py:obj:`file`-like object) + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` + + .. note:: The data on the stream are not directly an MJPEG stream. They need to be parsed according to VAPIX. + """ + api_call = 'axis-cgi/mjpg/video.cgi?camera=%d&fps=%d&resolution=%s&compression=%d&color=%d&squarepixel=%d' % ( + self.camera_id, fps, resolution_name, compression, 1 if use_color else 0, 1 if use_square_pixels else 0 + ) + + url = self._form_api_url(api_call) + return self._open_url(url, valid_statuses=[200]) + + def is_video_ok(self): + """Check using API whether the video source is ready and streaming. + + :return: If the video source is OK. + :rtype: :py:class:`bool` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` + + .. note:: Unfortunately, not all video errors are recognized (e.g. the black-image stream). + """ + url = self._form_api_url("axis-cgi/view/videostatus.cgi?status=%d" % self.camera_id) + response_line = self._read_oneline_response(url) + status = self.parse_parameter_and_value_from_response_line(response_line)[1] + + return status == "video" + + @staticmethod + def read_next_image_from_video_stream(stream): + """Read the next image header and image from the stream, skipping any irrelevant data in the stream. + + The stream is supposed to be in a state such that an image and the empty line after it have just been read (or + at the very start of the stream). + + :param stream: The video stream. + :type stream: :py:class:`urllib.addinfourl` + :return: Video frame header and the frame. Return (None, None) if reading the image fails. The frame is in JPG. + :rtype: tuple (dict, :py:obj:`basestring`) + :raises: :py:exc:`IOError`, :py:exc:`urllib.URLError` If reading from the stream fails. + """ + found_boundary = VAPIX._find_boundary_in_stream(stream) + if not found_boundary: + return None, None + + return VAPIX._read_image_from_stream(stream) + + @staticmethod + def _find_boundary_in_stream(stream): + """The string "--myboundary" is used to denote the start of an image in Axis cameras. + + :param stream: The video stream. + :type stream: urllib.addinfourl + :return: Returns False if end of stream was reached. + :rtype: :py:class:`bool` + :raises: :py:exc:`IOError`, :py:exc:`urllib.URLError` If reading from the stream fails. + """ + while not rospy.is_shutdown(): + line = stream.readline() + if line is None: + # end of stream + return False + if line == '--myboundary\r\n': + return True + # throw away all other data until a boundary is found + + @staticmethod + def _read_image_from_stream(stream): + """Get the image header and image itself. + + The stream is supposed to be in a state such that the boundary is the last line read from the stream. + + :param stream: The video stream. + :type stream: urllib.addinfourl + :return: Video header and the frame. Return (None, None) if reading the image fails. The frame is in JPG. + :rtype: tuple (dict, :py:obj:`basestring`) + :raises: :py:exc:`IOError`, :py:exc:`urllib.URLError` If reading from the stream fails. + """ + header = VAPIX._get_image_header_from_stream(stream) + + image = None + if header['Content-Length'] > 0: + content_length = int(header['Content-Length']) + image = VAPIX._get_image_data_from_stream(stream, content_length) + else: + return None, None + + return header, image + + @staticmethod + def _get_image_header_from_stream(stream): + """Read an HTTP-like header of the next video stream. + + The stream is supposed to be in a state such that the boundary is the last line read from the stream. + + :param stream: The video stream. + :type stream: urllib.addinfourl + :return: A dcitionary of HTTP-like headers. Most notably, the 'Content-Length' denotes the byte-size of the next + video frame, which follows right after this header in the stream. + :rtype: dict + :raises: :py:exc:`IOError`, :py:exc:`urllib.URLError` If reading from the stream fails. + """ + header = {} + while not rospy.is_shutdown(): + line = stream.readline() + if line == "\r\n": # the header is finished with an empty line + break + line = line.strip() + parts = line.split(": ", 1) + + if len(parts) != 2: + rospy.logwarn('Problem encountered with image header. Setting content_length to zero. The problem ' + 'header was: "%s"' % line) + header['Content-Length'] = 0 # set content_length to zero if there is a problem reading header + else: + try: + header[parts[0]] = parts[1] + except KeyError, e: + rospy.logwarn('Problem encountered with image header. Invalid header key: %r' % e) + header['Content-Length'] = 0 # set content_length to zero if there is a problem reading header + + return header + + @staticmethod + def _get_image_data_from_stream(stream, num_bytes): + """Get the binary image data itself (ie. without header) + + The stream is supposed to be in a state such that the empty line after header is the last line read from the + stream. + + :param stream: The video stream. + :type stream: urllib.addinfourl + :param num_bytes: The byte-size of the video frame. + :type num_bytes: int + :return: The byte data of the video frame (encoded as JPG). + :rtype: :py:class:`str` + :raises: :py:exc:`IOError`, :py:exc:`urllib.URLError` If reading from the stream fails. + """ + image = stream.read(num_bytes) + stream.readline() # Read terminating \r\n and do nothing with it + return image + + def resolve_video_resolution_name(self, name): + """Return the width and height corresponding to the given resolution name. + + :param basestring name: Name of the resolution. If None is given, the camera's default resolution is returned. + May only be one of the string returned in Properties.Image.Resolution param (and only + those not of a form `width`x`height`). + :return: The width and height corresponding to the resolution. + :rtype: tuple + + :raises: :py:exc:`ValueError` if the resolution name is not known to the camera + """ + + api_url = self._form_imagesize_url() + "&squarepixel=0" + if name is not None: # None name means we want to get the camera's default resolution + api_url += "&resolution=%s" % name + + response_lines = self._read_multiline_response(api_url, self.connection_timeout) + if len(response_lines) != 2: + raise ValueError("Resolution with name '%s' could not be resolved. The API response is %r." % + (name, response_lines)) + + width = int(self.parse_parameter_and_value_from_response_line(response_lines[0])[1]) + height = int(self.parse_parameter_and_value_from_response_line(response_lines[1])[1]) + + return width, height + + def get_camera_position(self, get_zoom=True, get_focus=True, get_iris=True): + """Get current camera PTZ position. + + :param get_zoom: If true, also try to get zoom. Set to false if using with no-zoom cameras. + :type get_zoom: bool + :param get_focus: If true, also try to get autofocus and focus. Set to false if using with no-focus cameras. + Value True is deprecated. + :type get_focus: bool + :param get_iris: If true, also try to get autoiris and iris. Set to false if using with no-iris cameras. + Value True is deprecated. + :type get_iris: bool + :return: The current camera position. + :rtype: dict {'pan': ..., 'tilt': ..., ['zoom': ...]} + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` + + .. note:: The get_focus and get_iris parameters are only supported for backwards compatibility. + """ + url = self._form_api_url("axis-cgi/com/ptz.cgi?query=position&camera=%d" % self.camera_id) + response_lines = self._read_multiline_response(url) + + position_keys = {'pan', 'tilt'} + if get_zoom: + position_keys.add('zoom') + if get_focus: # deprecated + position_keys.add('autofocus') + position_keys.add('focus') + if get_iris: # deprecated + position_keys.add('autoiris') + position_keys.add('iris') + + # now read everything returned in the API response and pick up the data we are requested for + position = dict() + for line in response_lines: + (key, value) = self.parse_parameter_and_value_from_response_line(line) + if key in position_keys: + if not key.startswith('auto'): + position[key] = float(value) + else: + position[key] = True if value == 'on' else False + + if 'pan' not in position or 'tilt' not in position or (get_zoom and 'zoom' not in position): + rospy.logdebug('Only succeeded to parse the following position values: %r' % position) + raise RuntimeError('Error requesting the current position of the camera. Unexpected API response.') + + return position + + def take_snapshot(self): + """Take a snapshot at the current camera's position. + + :return: The binary data of the image. + :rtype: :py:obj:`bytes` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` + + .. todo:: Implement more snapshotting functionality. + """ + image_data = self._read_binary_response(self._form_api_url("axis-cgi/jpg/image.cgi?camera=%d" % self.camera_id)) + return image_data + + def restart_camera(self): + """Restart (re-initialize) the camera. + + This requires admin credentials to be given when creating this API instance. + """ + rospy.loginfo("Restarting camera %d on %s ." % (self.camera_id, self.hostname)) + self._call_api_no_response("axis-cgi/admin/restart.cgi") + + # and now try to reload camera capabilities which might have changed after restart + # (here we also just wait until the camera is ready again) + while not rospy.is_shutdown(): + try: + self._has_ptz = self.has_ptz() + if self._has_ptz: + self._ptz_capabilities = self._get_ptz_capabilities() + self.ptz_limits = self._get_ptz_limits() + break + except (IOError, ValueError, RuntimeError): + rospy.logdebug("Cannot get camera capabilities. Waiting 1s.") + rospy.sleep(1) + + ################ + # PTZ movement # + ################ + + def move_ptz_absolute(self, pan=None, tilt=None, zoom=None): + """Command the PTZ unit with an absolute pose. + + :param pan: The desired pan. In None, pan is not commanded at all. + The value is automatically normalized to <-180,+180> + :type pan: float + :param tilt: The desired tilt. In None, tilt is not commanded at all. + The value is automatically normalized to <-180,+180> + :type tilt: float + :param zoom: The desired zoom level. In None, zoom is not commanded at all. + :type zoom: int + :return: The pan, tilt and zoom values that were really applied (e.g. the cropped and normalized input) + :rtype: tuple + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + from -170 to +170 pan is requested). + + .. note:: Since the pan and tilt values are periodic and normalization takes place in this function, you can + simply call this command in loops like e.g. `for pan in range(0,3600,30): move_ptz_absolute(pan)` + to rotate the camera 10 times. + """ + commands = [] + if pan is not None: + self.require_capabilities('AbsolutePan') + pan = self.ptz_limits['Pan'].absolute.crop_value(pan) + commands.append("pan=%f" % pan) + + if tilt is not None: + self.require_capabilities('AbsoluteTilt') + tilt = self.ptz_limits['Tilt'].absolute.crop_value(tilt) + commands.append("tilt=%f" % tilt) + + if zoom is not None: + self.require_capabilities('AbsoluteZoom') + zoom = self.ptz_limits['Zoom'].absolute.crop_value(zoom) + commands.append("zoom=%d" % zoom) + + if len(commands) > 0: + command = "&".join(commands) + self._call_ptz_command(command) + + return pan, tilt, zoom + + def move_ptz_relative(self, pan=None, tilt=None, zoom=None): + """Command the PTZ unit with a relative pose shift. + + :param pan: The pan change. In None or 0, pan remains unchanged. + The value is automatically normalized to <-360,+360>. May be negative. + :type pan: float + :param tilt: The tilt change. In None or 0, tilt remains unchanged. + The value is automatically normalized to <-360,+360>. May be negative. + :type tilt: float + :param zoom: The zoom change. In None or 0, zoom remains unchanged. May be negative. + :type zoom: int + :return: The pan, tilt and zoom change values that were really applied (e.g. the cropped and normalized input) + :rtype: tuple + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution (which might take a while if e.g. a move + by 300 deg pan is requested). + """ + commands = [] + + if pan is not None: + self.require_capabilities('RelativePan') + pan = self.ptz_limits['Pan'].relative.crop_value(pan) + commands.append("rpan=%f" % pan) + + if tilt is not None: + self.require_capabilities('RelativeTilt') + tilt = self.ptz_limits['Tilt'].relative.crop_value(tilt) + commands.append("rtilt=%f" % tilt) + + if zoom is not None: + self.require_capabilities('RelativeZoom') + zoom = self.ptz_limits['Zoom'].relative.crop_value(zoom) + commands.append("rzoom=%d" % zoom) + + if len(commands) > 0: + command = "&".join(commands) + self._call_ptz_command(command) + + return pan, tilt, zoom + + def set_ptz_velocity(self, pan=None, tilt=None, zoom=None): + """Command the PTZ unit velocity in terms of pan, tilt and zoom. + + :param pan: Pan speed. In None, pan remains unchanged. Pan speed is aperiodic (can be higher than 360). + May be negative. + :type pan: int + :param tilt: Tilt speed. In None, tilt remains unchanged. Tilt speed is aperiodic (can be higher than 360). + May be negative. + :type tilt: int + :param zoom: Zoom speed. In None or 0, zoom remains unchanged. May be negative. + :type zoom: int + :return: The pan, tilt and zoom velocity values that were really applied (e.g. the cropped and normalized input) + :rtype: tuple + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + + .. note:: This call doesn't wait for the command to finish execution. + + .. note:: It is not clearly stated in the API, but practically any following absolute/relative pose command + sets velocity to zero. + """ + commands = [] + + if pan is not None or tilt is not None: + if pan is not None: + self.require_capabilities('ContinuousPan') + pan = self.ptz_limits['Pan'].velocity.crop_value(pan) + else: + pan = 0 + + if tilt is not None: + self.require_capabilities('ContinuousTilt') + tilt = self.ptz_limits['Tilt'].velocity.crop_value(tilt) + else: + tilt = 0 + + commands.append("continuouspantiltmove=%d,%d" % (pan, tilt)) + + if zoom is not None: + self.require_capabilities('ContinuousZoom') + zoom = self.ptz_limits['Zoom'].velocity.crop_value(zoom) + commands.append("continuouszoommove=%d" % zoom) + + if len(commands) > 0: + command = "&".join(commands) + self._call_ptz_command(command) + + return pan, tilt, zoom + + def look_at(self, x, y, image_width, image_height): + """Point the camera center to a point with the given coordinates in the camera image. + + :param x: X coordinate of the look-at point. + :type x: int + :param y: X coordinate of the look-at point. + :type y: int + :param image_width: Width of the image in pixels. + :type image_width: int + :param image_height: Height of the image in pixels. + :type image_height: int + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + + .. todo:: A workaround for cameras without this functionality but with relative zoom support. + """ + # these capabilities do not in fact ensure the capability needed for the center command, but better than nothing + self.require_capabilities('AbsolutePan', 'AbsoluteTilt', 'AbsoluteZoom') + + self._call_ptz_command("center=%d,%d&imagewidth=%d&imageheight=%d" % (x, y, image_width, image_height)) + + ######### + # Focus # + ######### + + def use_autofocus(self, use): + """Command the camera to use/stop using autofocus. + + :param use: True: use autofocus; False: do not use it. + :type use: bool + :return: use + :rtype: :py:class:`bool` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + self.require_capabilities('AutoFocus') + self._call_ptz_command("autofocus=%s" % "on" if use else "off") + return use + + def set_focus(self, focus): + """Set focus to the desired value (implies turning off autofocus). + + :param focus: The desired focus value. + :type focus: int + :return: The focus value that was really applied (e.g. the cropped and normalized input) + :rtype: :py:class:`int` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + self.require_capabilities('AbsoluteFocus') + focus = self.ptz_limits['Focus'].absolute.crop_value(focus) + self._call_ptz_command("autofocus=off&focus=%d" % focus) + return focus + + def adjust_focus(self, amount): + """Add the desired amount to the focus value (implies turning off autofocus). + + :param amount: The desired focus change amount. + :type amount: int + :return: The focus change amount that was really applied (e.g. the cropped and normalized input) + :rtype: :py:class:`int` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + self.require_capabilities('RelativeFocus') + amount = self.ptz_limits['Focus'].relative.crop_value(amount) + self._call_ptz_command("autofocus=off&rfocus=%d" % amount) + return amount + + def set_focus_velocity(self, velocity): + """Set the focus "speed" (implies turning off autofocus). + + :param velocity: The desired focus velocity. + :type velocity: int + :return: The focus velocity that was really applied (e.g. the cropped and normalized input) + :rtype: :py:class:`int` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + self.require_capabilities('ContinuousFocus') + velocity = self.ptz_limits['Focus'].velocity.crop_value(velocity) + self._call_ptz_command("autofocus=off&countinuousfocusmove=%d" % velocity) + return velocity + + # Iris + def use_autoiris(self, use): + """Command the camera to use/stop using auto iris adjustment. + + :param use: True: use auto iris adjustment; False: do not use it. + :type use: bool + :return: use + :rtype: :py:class:`bool` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + self.require_capabilities('AutoIris') + self._call_ptz_command("autoiris=%s" % "on" if use else "off") + return use + + def set_iris(self, iris): + """Set iris to the desired value (implies turning off autoiris). + + :param iris: The desired iris value. + :type iris: int + :return: The iris value that was really applied (e.g. the cropped and normalized input) + :rtype: :py:class:`int` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + self.require_capabilities('AbsoluteIris') + iris = self.ptz_limits['Iris'].absolute.crop_value(iris) + self._call_ptz_command("autoiris=off&iris=%d" % iris) + return iris + + def adjust_iris(self, amount): + """Add the desired amount to the iris value (implies turning off autoiris). + + :param amount: The desired iris change amount. + :type amount: int + :return: The iris change amount that was really applied (e.g. the cropped and normalized input) + :rtype: :py:class:`int` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + self.require_capabilities('RelativeIris') + amount = self.ptz_limits['Iris'].relative.crop_value(amount) + self._call_ptz_command("autoiris=off&riris=%d" % amount) + return amount + + def set_iris_velocity(self, velocity): + """Set the iris "speed" (implies turning off autoiris). + + :param velocity: The desired iris velocity. + :type velocity: int + :return: The iris velocity that was really applied (e.g. the cropped and normalized input) + :rtype: :py:class:`int` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + self.require_capabilities('ContinuousIris') + velocity = self.ptz_limits['Iris'].velocity.crop_value(velocity) + self._call_ptz_command("autoiris=off&countinuousirismove=%d" % velocity) + return velocity + + # Brightness + def set_brightness(self, brightness): + """Set brightness to the desired value. + + :param brightness: The desired brightness value. + :type brightness: int + :return: The brightness value that was really applied (e.g. the cropped and normalized input) + :rtype: :py:class:`int` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + + .. note:: The brightness setting has no effect on Axis 214 PTZ. + """ + # self.require_capabilities('AbsoluteBrightness') # this capability is not present in the list + brightness = self.ptz_limits['Brightness'].absolute.crop_value(brightness) + self._call_ptz_command("brightness=%d" % brightness) + return brightness + + def adjust_brightness(self, amount): + """Add the desired amount to the brightness value. + + :param amount: The desired brightness change amount. + :type amount: int + :return: The brightness change amount that was really applied (e.g. the cropped and normalized input) + :rtype: :py:class:`int` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + + .. note:: The brightness setting has no effect on Axis 214 PTZ. + """ + self.require_capabilities('RelativeBrightness') + amount = self.ptz_limits['Brightness'].relative.crop_value(amount) + self._call_ptz_command("rbrightness=%d" % amount) + return amount + + def set_brightness_velocity(self, velocity): + """Set the brightness "speed". + + :param velocity: The desired brightness velocity. + :type velocity: int + :return: The brightness velocity that was really applied (e.g. the cropped and normalized input) + :rtype: :py:class:`int` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + + .. note:: The brightness setting has no effect on Axis 214 PTZ. + """ + self.require_capabilities('ContinuousBrightness') + velocity = self.ptz_limits['Brightness'].velocity.crop_value(velocity) + self._call_ptz_command("countinuousbrightnessmove=%d" % velocity) + return velocity + + ########################## + # Backlight compensation # + ########################## + + def use_backlight_compensation(self, use): + """Command the camera to use/stop using backlight compensation (requires autoiris=on set before). + + :param use: True: use backlight compensation; False: do not use it. + :type use: bool + :return: use + :rtype: :py:class:`bool` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + self.require_capabilities('BackLight') + self._call_ptz_command("backlight=%s" % ("on" if use else "off")) + return use + + ################### + # Infrared filter # + ################### + + def use_ir_cut_filter(self, use): + """Command the camera to use/stop using infrared filter. + + :param use: None: Automatic mode (requires autoiris=on set before); + True: use infrared filter; + False: do not use it. + :type use: bool + :return: use + :rtype: :py:class:`bool` + + :raises: :py:exc:`RuntimeError` if the camera doesn't have capabilities to execute the given command. + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + self.require_capabilities('IrCutFilter') + self._call_ptz_command("ircutfilter=%s" % ("auto" if use is None else ("on" if use else "off"))) + return use + + ####################### + # PTZ presence checks # + ####################### + + def has_ptz(self): + """Returns True if a PTZ unit is available for the connected camera (according to the API). + + :return: Whether PTZ is available. + :rtype: :py:class:`bool` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + return self.get_parameter("root.Properties.PTZ.PTZ") == "yes" + + def is_digital_ptz(self): + """Returns True if a the PTZ unit is digital (i.e. has no mechanical parts). + + :return: Whether PTZ is digital or not. + :rtype: :py:class:`bool` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + return self.get_parameter("root.Properties.PTZ.DigitalPTZ") == "yes" + + ############################### + # Camera and PTZ capabilities # + ############################### + + def has_capability(self, capability): + """Tell whether the camera has the given capability. + + The list of capabilities is only queried once when connecting to the API, and calls to this method use the + cached list of detected capabilities. + + :param capability: Name of the capability to test. E.g. 'AbsolutePan', 'ContinuousZoom' and so on (as defined + in VAPIX parameter group root.PTZ.Support) + :type capability: basestring + :return: Whether the camera has the given capability or not. + :rtype: :py:class:`bool` + """ + if not self._has_ptz: + return False + return capability in self._ptz_capabilities + + def has_capabilities(self, *capabilities): + """Tell whether the camera has all of the given capabilities. + + The list of capabilities is only queried once when connecting to the API, and calls to this method use the + cached list of detected capabilities. + + :param capabilities: Names of the capabilities to test. E.g. 'AbsolutePan', 'ContinuousZoom' and so on + (as defined in VAPIX parameter group root.PTZ.Support) + :type capabilities: list of :py:obj:`basestring` + :return: Whether the camera has all the given capabilities or not. + :rtype: :py:class:`bool` + """ + if not self._has_ptz: + return False + + for capability in capabilities: + if not self.has_capability(capability): + return False + + return True + + def require_capabilities(self, *capabilities): + """Raise a :py:exc:`RuntimeError` if the camera doesn't have all of the given capabilities. + + The list of capabilities is only queried once when connecting to the API, and calls to this method use the + cached list of detected capabilities. + + :param capabilities: Names of the capabilities to require. E.g. 'AbsolutePan', 'ContinuousZoom' and so on + (as defined in VAPIX parameter group root.PTZ.Support) + :type capabilities: list of :py:obj:`basestring` + :raises: :py:exc:`RuntimeError` if the camery doesn't have one of the required capabilities. + """ + for capability in capabilities: + if not self.has_capability(capability): + raise RuntimeError("Camera %d on host %s doesn't support the required capability %s." % ( + self.camera_id, self.hostname, capability)) + + def _get_ptz_capabilities(self): + """Read the list of capabilities from the camera. + + :return: The list of capabilities. + :rtype: list + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + prefix = "root.PTZ.Support.S%d" % self.camera_id + parameters = self.get_parameter_list(prefix) + + result = set() + for (key, value) in parameters.iteritems(): + if value == "true": + key_stripped = key.replace(prefix + ".", "") + result.add(key_stripped) + + return result + + ############## + # PTZ limits # + ############## + + def _get_ptz_limits(self): + """Return the list of effective limits of the PTZ control parameters. + + Effective means it is a combination of the VAPIX specifications and real limits read from the camera. + + :return: The limits of the PTZ control of the connected camera. Keys are 'Pan', 'Tilt' and so on. + :rtype: dict (:py:obj:`basestring` => :py:class:`PTZLimit`) + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + real_limits = self._get_real_ptz_limits() + api_limits = self._get_api_ptz_limits() + + result = dict() + # get the set of keys present in at least one of the two limit dicts + keys = set().union(real_limits.keys()).union(api_limits.keys()) + + # create the result so that if a limit is only in one dict, then just copy it, and when it is in both dicts, + # put a merged limit in the result + for key in keys: + if key not in real_limits.keys(): + if key in api_limits.keys(): + result[key] = api_limits[key] + elif key not in api_limits.keys(): + if key in real_limits.keys(): + result[key] = real_limits[key] + else: + result[key] = api_limits[key].merge(real_limits[key]) + + return result + + def _get_real_ptz_limits(self): + """Get the list of actual PTZ limits read from the camera. + + :return: The limits of the PTZ control of the connected camera. Keys are 'Pan', 'Tilt' and so on. + :rtype: dict (:py:obj:`basestring` => :py:class:`PTZLimit`) + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + """ + prefix = "root.PTZ.Limit.L%d" % self.camera_id + parameters = self.get_parameter_list(prefix) + + result = dict() + for (key, value) in parameters.iteritems(): + key_stripped = key.replace(prefix + ".", "") + + limit = float(value) + capability = key_stripped.replace("Min", "").replace("Max", "") + + if capability not in result.keys(): + result[capability] = PTZLimit() + + if key_stripped.startswith("Min"): + result[capability].absolute.min = limit + else: + result[capability].absolute.max = limit + + result['Pan'].absolute.period = 360 + result['Tilt'].absolute.period = 360 + + return result + + @staticmethod + def _get_api_ptz_limits(): + """Get the list of PTZ limits specified by VAPIX. + + :return: The PTZ control limits. Keys are 'Pan', 'Tilt' and so on. + :rtype: dict (:py:obj:`basestring` => :py:class:`PTZLimit`) + """ + return { + 'Pan': PTZLimit(absolute=Range(-180, 180, 360), relative=Range(-360, 360, 720), velocity=Range(-100, 100)), + 'Tilt': PTZLimit(absolute=Range(-180, 180, 360), relative=Range(-360, 360, 720), velocity=Range(-100, 100)), + 'Zoom': PTZLimit(absolute=Range(1, 9999), relative=Range(-9999, 9999), velocity=Range(-100, 100)), + 'Focus': PTZLimit(absolute=Range(1, 9999), relative=Range(-9999, 9999), velocity=Range(-100, 100)), + 'Iris': PTZLimit(absolute=Range(1, 9999), relative=Range(-9999, 9999), velocity=Range(-100, 100)), + 'Brightness': PTZLimit(absolute=Range(1, 9999), relative=Range(-9999, 9999), velocity=Range(-100, 100)), + } + + ###################### + # Parameter handling # + ###################### + + def get_parameter(self, name): + """Get the value of the specified parameter through VAPIX. + + :param name: Full name of the parameter (e.g. 'root.Properties.PTZ.PTZ'). + :type name: basestring + :return: The value of the parameter. + :rtype: :py:obj:`basestring` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + :raises: :py:exc:`ValueError` if response to the parameter request cannot be parsed + """ + url = self._form_parameter_url(name) + response_line = self._read_oneline_response(url) + value = self.parse_parameter_and_value_from_response_line(response_line) + return value[1] + + def get_parameter_list(self, group): + """Get the values of all parameters under the specified parameter group through VAPIX. + + :param group: Full name of the group (e.g. 'root.Properties'). + :type group: basestring + :return: The values of the parameters. + :rtype: dict(:py:obj:`basestring` => :py:obj:`basestring`) + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network communication error + :raises: :py:exc:`ValueError` if response to the parameter request cannot be parsed + """ + url = self._form_parameter_url(group) + response_lines = self._read_multiline_response(url) + + result = dict() + for response_line in response_lines: + parameter_and_value = self.parse_parameter_and_value_from_response_line(response_line) + result[parameter_and_value[0]] = parameter_and_value[1] + + return result + + ######################## + # API HELPER FUNCTIONS # + ######################## + + def _form_api_url(self, api_call): + """Return the URL to be called to execute the given API call. + + :param api_call: The API call without hostname and slash, e.g. "axis-cgi/param.cgi?camera=1". + :type api_call: basestring + :return: The URL. + :rtype: :py:obj:`basestring` + """ + return "http://%s/%s" % (self.hostname, api_call) + + def _call_api_no_response(self, api_call): + """Call the given API command expecting no content in response. + + :param api_call: The API call without hostname and slash, e.g. "axis-cgi/param.cgi?camera=1". + :type api_call: basestring + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network error or invalid HTTP status of the + API response + """ + with closing( + self._open_url(self._form_api_url(api_call), valid_statuses=[204], timeout=self.connection_timeout)): + pass + + def _call_api_oneline_response(self, api_call): + """Call the given API command expecting a one-line result. + + :param api_call: The API call without hostname and slash, e.g. "axis-cgi/param.cgi?camera=1". + :type api_call: basestring + :return: The response text line (without newline at the end). + :rtype: :py:obj:`basestring` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network error or invalid HTTP status of the + API response + """ + return self._read_oneline_response(self._form_api_url(api_call), self.connection_timeout) + + def _call_api_multiline_response(self, api_call): + """Call the given API command expecting a multiline result. + + :param api_call: The API call without hostname and slash, e.g. "axis-cgi/param.cgi?camera=1". + :type api_call: basestring + :return: The response text lines (without newlines at the end). + :rtype: list of :py:obj:`basestring` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network error or invalid HTTP status of the API response + """ + return self._read_multiline_response(self._form_api_url(api_call), self.connection_timeout) + + def _call_api_binary_response(self, api_call): + """Call the given API command expecting a binary result (e.g. an image). + + :param api_call: The API call without hostname and slash, e.g. "axis-cgi/param.cgi?camera=1". + :type api_call: basestring + :return: The response data. + :rtype: :py:obj:`bytes` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network error or invalid HTTP status of the API response + """ + return self._read_binary_response(self._form_api_url(api_call), self.connection_timeout) + + def _call_ptz_command(self, command): + """Call the given PTZ command. + + :param command: The command to execute. It is an ampersand-delimited string of type 'pan=1&tilt=5'. + :type command: basestring + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network error or invalid HTTP status of the API response + """ + + rospy.logdebug("Calling PTZ command %s on host %s, camera %d" % (command, self.hostname, self.camera_id)) + self._call_api_no_response("axis-cgi/com/ptz.cgi?camera=%d&%s" % (self.camera_id, command)) + + ################################################################# + # Static API that can be used before obtaining a VAPIX instance # + ################################################################# + + @staticmethod + def _open_url(url, valid_statuses=None, timeout=2): + """Open connection to Axis camera using HTTP + + :param url: The full URL to query. + :type url: basestring + :param valid_statuses: Status codes denoting valid responses. Other codes will raise an IOException. If None, + the reposnse status code is not examined. + :type valid_statuses: list of int + :param timeout: Timeout for the request. + :type timeout: int + :return: The stream with the response. The stream is never None (IOException would be thrown in such case). + :rtype: :py:class:`urllib.addinfourl` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network error or invalid HTTP status of the + API response + """ + rospy.logdebug('Opening VAPIX URL %s .' % url) + try: + stream = urllib2.urlopen(url, timeout=timeout) + except socket.timeout, e: # sometimes the socket.timeout error is not correctly wrapped in URLError + raise urllib2.URLError(e) + + if stream is not None: + # check the response status + if valid_statuses is None or stream.getcode() in valid_statuses: + return stream + else: + if int(stream.getcode()) == 401: + raise IOError('Authentication required to access VAPIX URL %s . Either provide login credentials or' + ' set up anonymous usage in the camera setup.' % url) + elif int(stream.getcode()) == 200: + # if we e.g. expect only 204 No Content, and we receive something, it is an error + line = stream.readline().strip() + if line == "Error:": + line = stream.readline().strip() + raise RuntimeError('Request %s ended with error %s.' % (url, line)) + else: + raise IOError( + 'Received HTTP code %d in response to API request at URL %s .' % (stream.getcode(), url)) + else: + raise IOError( + 'Received HTTP code %d in response to API request at URL %s .' % (stream.getcode(), url)) + else: + raise IOError('Error opening URL %s .' % url) + + @staticmethod + def _read_oneline_response(url, timeout=2): + """Call the given full URL expecting a one-line response and return it. + + :param url: The full URL to query. + :type url: basestring + :param timeout: Timeout for the request. + :type timeout: int + :return: The response text line (without newline at the end). + :rtype: :py:obj:`basestring` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network error or invalid HTTP status of the + API response + """ + with closing(VAPIX._open_url(url, valid_statuses=[200], timeout=timeout)) as response_stream: + line = response_stream.readline() + + if line is None: + raise IOError("Error reading response for API request at URL %s ." % url) + + if line.strip() == "Error:": + line = response_stream.readline().strip() + raise RuntimeError("API request %s returned error: %s" % (url, line)) + + return line.strip("\n") + + @staticmethod + def _read_multiline_response(url, timeout=2): + """Call the given full URL expecting a multiline result. + + :param url: The full URL to query. + :type url: basestring + :param timeout: Timeout for the request. + :type timeout: int + :return: The response text lines (without newlines at the end). + :rtype: list of :py:obj:`basestring` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network error or invalid HTTP status of the + API response + """ + with closing(VAPIX._open_url(url, valid_statuses=[200], timeout=timeout)) as response_stream: + lines = [] + + while not rospy.is_shutdown(): + line = response_stream.readline() + + if line is None or len(line) == 0 or line == "\n": + break + + if line.strip() == "Error:": + line = response_stream.readline().strip() + raise RuntimeError("API request %s returned error: %s" % (url, line)) + + lines.append(line.strip()) + + return lines + + @staticmethod + def _read_binary_response(url, timeout=2): + """Read a binary result for a given full URL (e.g. an image). + + :param url: The full URL to query. + :type url: basestring + :param timeout: Timeout for the API request. + :type timeout: int + :return: The response data. + :rtype: :py:obj:`bytes` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` + """ + with closing(VAPIX._open_url(url, valid_statuses=[200], timeout=timeout)) as response_stream: + return response_stream.read() + + @staticmethod + def parse_parameter_and_value_from_response_line(line): + """Parse an API response line of the form key=value. + + :param line: The response line to parse. + :type line: :py:obj:`str` | :py:obj:`unicode` + :return: The parsed tuple (key, value). + :rtype: tuple + :raises: :py:exc:`ValueError` When the line cannot be parsed. + """ + parts = line.split("=", 2) + if len(parts) == 2: + return parts[0].strip(), parts[1].strip() + + raise ValueError("Line '%s' is not a valid key-value parameter API reponse line." % line) + + @staticmethod + def parse_list_parameter_value(list_value): + """Parse an API response value that is a list and return the list. + + :param list_value: The value to be parsed as a (comma separated) list. + :type list_value: :py:obj:`str` | :py:obj:`unicode` + :return: The list of parsed values. + :rtype: list of :py:obj:`basestring` + """ + return list_value.split(",") + + @staticmethod + def wakeup_camera(hostname, camera_id): + """Try to wake up a camera in standby mode. + + :param hostname: Hostname of the camera. + :type hostname: basestring + :param camera_id: Id of the camera. Usually 1-4. + :type camera_id: int + :raises: :py:exc:`IOError`, :py:exc:`urllib2.URLError` on network error or invalid HTTP status of the + API response + """ + # TODO what to do if there is no PTZ support? + url = 'http://%s/axis-cgi/com/ptz.cgi?camera=%d&autofocus=on' % (hostname, camera_id) + with closing(VAPIX._open_url(url, valid_statuses=[200, 204])): + pass + + @staticmethod + def setup_authentication(hostname, username, password, use_encrypted_password=False): + """Set user credentials to the HTTP handler, so that if authentication is required, they will be used. + + :param hostname: Hostname of the camera. + :type hostname: basestring + :param username: Username. + :type username: basestring + :param password: Password. + :type password: basestring + :param use_encrypted_password: Whether to use Plain HTTP Auth (False) or Digest HTTP Auth (True). + :type use_encrypted_password: bool + """ + # create a password manager + password_manager = urllib2.HTTPPasswordMgrWithDefaultRealm() + + # Add the username and password, use default realm. + top_level_url = "http://%s" % hostname + password_manager.add_password(None, top_level_url, username, password) + + if use_encrypted_password: + handler = urllib2.HTTPDigestAuthHandler(password_manager) + else: + handler = urllib2.HTTPBasicAuthHandler(password_manager) + + # create "opener" (OpenerDirector instance) + opener = urllib2.build_opener(handler) + + # ...and install it globally so it can be used with urlopen. + urllib2.install_opener(opener) + + @staticmethod + def get_api_for_camera(hostname, username=None, password=None, camera_id=1, use_encrypted_password=False, + wakeup_on_fail=True): + """Return the VAPIX API instance corresponding to the autodetected API version (both v2 and v3 are supported). + + :param hostname: Hostname of the camera (without http://, may be an IP address). + :type hostname: basestring + :param username: If login is needed, provide a username here. + :type username: :py:obj:`basestring` | None + :param password: If login is needed, provide a password here. + :type password: :py:obj:`basestring` | None + :param int camera_id: ID (number) of the camera. Can be 1 to 4. + :param bool use_encrypted_password: Whether to use Plain HTTP Auth (False) or Digest HTTP Auth (True). + :param bool wakeup_on_fail: If connecting to the API fails, try to wake up the camera and retry connection. + :return: Autodetected API instance. + :rtype: :py:class:`VAPIX` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.ULRError`, :py:exc:`ValueError` If connecting to the API failed. + :raises: :py:exc:`RuntimeError` If unexpected values are returned by the API. + """ + VAPIX._using_authentication = False + # Enable HTTP login if a username and password are provided. + if username is not None and len(username) > 0 and password is not None: + rospy.logdebug("Using authentication credentials with user %s on host %s" % (username, hostname)) + VAPIX._using_authentication = True + VAPIX.setup_authentication(hostname, username, password, use_encrypted_password) + + # What can happen? + # 1. Try to read the API version parameter using v3 syntax. + # 1. a. The read succeeds -> return v3 API. + # 1. b. Unauthenticated HTTP error -> this happens in FW 5.0 - 5.6 -> return v3 API. + # 1. c. Any other error -> read the API version using v2 syntax. + # 1. c. A. The read succeeds -> return v2 API. + # 1. c. B. Unauthenticated error -> fail and tell the user to provide credentials in the next trial. + # 1. c. C. Any other error -> + # 1. c. C. I. Auto wakeup is enabled -> try the whole thing once more after waking up the camera. + # 1. c. C. II. Otherwise, report error to the user and give up. + + rospy.logdebug("Starting VAPIX autodetection.") + try: + try: + # First, try the v3 API. + return VAPIX._get_v3_api(hostname, camera_id) + except (IOError, ValueError): + # Next, try the v2 API. + try: + return VAPIX._get_v2_api(hostname, camera_id) + except (IOError, ValueError): + if wakeup_on_fail: + # Maybe the camera is in standby mode. Try to wake it up. + rospy.logdebug("First try on VAPIX autodetection failed. The camera may be in standby mode. " + "Trying to wake it up.") + VAPIX.wakeup_camera(hostname, camera_id) + + # After waking up, try again both API v3 and v2 + rospy.logdebug("Starting VAPIX autodetection - second try.") + return VAPIX.get_api_for_camera(hostname, username, password, camera_id, use_encrypted_password, + # we don't try to wake up the camera in the second try + False) + else: + # If we encountered an error and waking up is not desired, we have no more choices than give up + raise + except Exception as e: + if isinstance(e, urllib2.HTTPError) and e.code == 401: # Unauthorized + rospy.logerr("Could not connect to VAPIX on host %s. The camera requires authentication. " + "Either enable anonymous viewing (and connect to the camera on local network), or " + "provide username and password parameters to the launch file." % hostname) + else: + rospy.logerr("Could not autodetect or connect to VAPIX on host %s, camera %d. " + "The camera stream will be unavailable. Cause: %r, %s, %r" % + (hostname, camera_id, e, str(e), e.args)) + raise + + @staticmethod + def _get_v3_api(hostname, camera_id=1): + """Check if the camera supports VAPIX v3, and if it does, return a corresponding VAPIXv3 instance. + + :param hostname: Hostname of the camera (without http://, may be an IP address) + :type hostname: basestring + :param camera_id: ID (number) of the camera. Can be 1 to 4. + :type camera_id: int + :return: The VAPIXv3 instance. + :rtype: :py:class:`VAPIXv3` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.ULRError`, :py:exc:`ValueError` If connecting to the API failed. + :raises: :py:exc:`RuntimeError` If unexpected values are returned by the API. + """ + try: + response = VAPIX._read_oneline_response( + "http://%s/axis-cgi/param.cgi?camera=%d&action=list&group=root.Properties.API.HTTP.Version" % + (hostname, camera_id) + ) + version = VAPIX.parse_parameter_and_value_from_response_line(response)[1] + + if version != "3": + raise RuntimeError("Unexpected VAPIX version: %s" % version) + + rospy.loginfo("Autodetected VAPIX version 3 for communication with camera %d" % camera_id) + return VAPIXv3(hostname, camera_id) + except urllib2.HTTPError as e: + # This is a workaround for firmwares 5.0 - 5.6, which unfortunately always require login credentials + # to find out the API version, even if anonymous access is allowed. + if e.code == 401 and not VAPIX._using_authentication: # Unauthorized and no credentials + rospy.loginfo("Optimistically autodetected VAPIX version 3 for communication with camera %d, " + "based on the fact that querying the API version parameter requires authentication, " + "which should be specific for VAPIX v3 with pre-5.7 firmwares. But it can also mean " + "that the camera is not set up for anonymous access, and then you'd need to provide a " + "username and password." % camera_id) + return VAPIXv3pre57Firmware(hostname, camera_id) + else: + raise + + @staticmethod + def _get_v2_api(hostname, camera_id=1): + """Check if the camera supports VAPIX v2, and if it does, return a corresponding VAPIXv2 instance. + + :param hostname: Hostname of the camera (without http://, may be an IP address) + :type hostname: basestring + :param camera_id: ID (number) of the camera. Can be 1 to 4. + :type camera_id: int + :return: The VAPIXv2 instance. + :rtype: :py:class:`VAPIXv2` + :raises: :py:exc:`IOError`, :py:exc:`urllib2.ULRError`, :py:exc:`ValueError` If connecting to the API failed. + :raises: :py:exc:`RuntimeError` If unexpected values are returned by the API. + """ + response = VAPIX._read_oneline_response( + "http://%s/axis-cgi/view/param.cgi?camera=%d&action=list&group=root.Properties.API.HTTP.Version" % + (hostname, camera_id) + ) + version = int(VAPIX.parse_parameter_and_value_from_response_line(response)[1]) + + if not 0 < version < 3: + raise RuntimeError("Unexpected VAPIX version: %s" % version) + + rospy.loginfo("Autodetected VAPIX version %d for communication with camera %d" % (version, camera_id)) + return VAPIXv2(hostname, camera_id) + + +class VAPIXv2(VAPIX): + """A class representing the VAPIX API version 2. + + Most of the functionalities should be implemented in the parent class VAPIX. + Here, only version-specific implementations have their place. + """ + def __repr__(self): + return "VAPIXv2(hostname=%r, camera_id=%r, connection_timeout=%r)" % ( + self.hostname, self.camera_id, self.connection_timeout) + + def _form_parameter_url(self, group): + return self._form_api_url("axis-cgi/view/param.cgi?camera=%d&action=list&group=%s" % (self.camera_id, group)) + + def _form_imagesize_url(self): + return self._form_api_url("axis-cgi/view/imagesize.cgi?camera=%d" % self.camera_id) + + +class VAPIXv3(VAPIX): + """A class representing the VAPIX API version 3. + + Most of the functionalities should be implemented in the parent class VAPIX. + Here, only version-specific implementations have their place. + """ + + def __repr__(self): + return "VAPIXv3(hostname=%r, camera_id=%r, connection_timeout=%r)" % ( + self.hostname, self.camera_id, self.connection_timeout) + + def _form_parameter_url(self, group): + return self._form_api_url("axis-cgi/param.cgi?camera=%d&action=list&group=%s" % (self.camera_id, group)) + + def _form_imagesize_url(self): + return self._form_api_url("axis-cgi/imagesize.cgi?camera=%d" % self.camera_id) + + +class VAPIXv3pre57Firmware(VAPIXv3): + """ + This is for the firmwares 5.0 - 5.6 which have a different webserver than post-5.6 cameras. + + The main difference is that with the older FWs, you cannot query the API version parameter anonymousely. + """ + pass diff --git a/scripts/axis_camera/video_streaming.py b/scripts/axis_camera/video_streaming.py new file mode 100644 index 0000000..447b739 --- /dev/null +++ b/scripts/axis_camera/video_streaming.py @@ -0,0 +1,247 @@ +from contextlib import closing +import threading + +import rospy +from sensor_msgs.msg import CompressedImage +from axis_camera.vapix import VAPIX + + +class ImageStreamingThread(threading.Thread): + """ + A thread that handles streaming video from the camera. + + It supports pausing the video stream (e.g. when there is no receiver of the video data), which should lower the + usage of communications link with the camera. + """ + + def __init__(self, axis): + """Create the video streaming thread (in a paused state). + + :param axis: The parameter specifying class. + :type axis: :py:class:`axis.Axis` + """ + threading.Thread.__init__(self) + self.daemon = True # allow exiting the main program even if this thread is still running + + # TODO refactor so that we pass the parameters directly and not using self.axis + self._axis = axis + self._is_paused = True + + # BACKWARDS COMPATIBILITY LAYER + self.fp = None # deprecated + self.header = None # deprecated + self.img = None # deprecated + self.content_length = None # deprecated + + def run(self): + """ + This method is executed when the thread execution should start (for the first time only, do not call more times) + """ + self.resume() + + while not rospy.is_shutdown(): + self._stream() + + def resume(self): + """Start streaming if the video stream was paused.""" + self._is_paused = False + + def pause(self): + """Pause streaming if the video stream was streaming.""" + self._is_paused = True + + def is_paused(self): + """Return if the streaming thread is paused or not. + + :return bool: The paused status. + """ + return self._is_paused + + def _stream(self): + """Stream the video forever, taking into account the paused state. + + Try to stream again after a streaming error. + """ + while not rospy.is_shutdown(): + self._publish_frames_until_error() + + # if stream stays intact we shouldn't get to this + if not rospy.is_shutdown(): + rospy.logerr("Video stream error. Trying again in 2 seconds") + rospy.sleep(2) + + def _wakeup_camera(self): + """Wake up the camera from standby. + + This call is blocking and waits for some time so that the initialization should be more or less finished when + it finishes. + + :return: If the wakeup succeeded. + :rtype: :py:class:`bool` + """ + rospy.logdebug("Trying to wake up the camera.") + + try: + self._axis._api._wakeup_camera(self._axis.hostname, self._axis._camera_id) + + # if the wakeup succeeded, give the camera a while to initialize and then proceed further + rospy.loginfo("Camera wakeup succeeded, now waiting for the camera to initialize.") + rospy.sleep(5) + return True + except IOError, e: + rospy.logerr("Exception thrown when waking up the camera. Cause: %r" % e) + return False + + def _publish_frames_until_error(self): + """Continuous loop to publish images. Stops if an error occurs while reading the stream. + + Should also account for pausing/resuming (stop/start reading the stream), and video parameters changes. + These should not make this function exit, it should instead reconnect automatically. + """ + while not rospy.is_shutdown(): # publish until an error occurs (then, a return is called to end this loop) + + # if we are paused, wait for a resume before connecting to the stream + while not rospy.is_shutdown() and (self._is_paused or not self._is_video_ok()): + rospy.sleep(1) + + try: # now try to open the video stream; + with closing( + self._axis._api.get_video_stream(self._axis._fps, self._axis._resolution.name, self._axis._compression, + self._axis._use_color, self._axis._use_square_pixels) + ) as stream: + + self.fp = stream # backwards compatibility + + # this is the rate at which we wake up to read new data; there is no need for it to happen faster + # than at the requested FPS + rate = rospy.Rate(self._axis._fps) + + # we've just crerated a video stream with the most recently requested parameters, so clear the dirty + # flag + self._axis.video_params_changed = False + + # publish images from the stream until i) someone pauses us, or ii) video parameters changed + # when one of these events happens, we take a next iteration of the outermost loop, in which there + # is a wait in case of pausing, and a new video stream connection is created with most recent + # parameters + while not rospy.is_shutdown() and not self._axis.video_params_changed and not self._is_paused: + try: + (header, image) = VAPIX.read_next_image_from_video_stream(stream) + if image is not None: + timestamp = rospy.Time.now() + self._publish_image(header, image, timestamp) + self._publish_camera_info(header, image, timestamp) + else: + # probably a temporary error, don't return + rospy.logwarn("Retrieving image from Axis camera failed.") + except IOError, e: + # error occured, we should therefore return + rospy.loginfo('Error reading from the video stream. Cause: %r' % e) + return + + # read images only on the requested FPS frequency + rate.sleep() + + except IOError, e: + # could not open the stream, the camera is probably in standby mode? + if self._axis.auto_wakeup_camera: + wakeup_succeeded = self._wakeup_camera() + if not wakeup_succeeded: + # if we could not wake up the camera, it is an error and we should return + rospy.logerr("%r" % e) + return + else: + continue + else: + # if we cannot open the stream and auto-wakeup is off, we have no other possibility than to report + # error + rospy.logerr("%r" % e) + return + + # the image-publishing loop has been interrupted, so reconnect to the stream in the next + # outer-while iteration + + if self._axis.video_params_changed: + rospy.logdebug("Video parameters changed, reconnecting the video stream with the new ones.") + + def _is_video_ok(self): + """Return True if the video stream is in good condition. + + :return: True if the video stream is in good condition. + :rtype: :py:class:`bool` + """ + try: + return self._axis._api.is_video_ok() + except IOError, e: + rospy.logerr(repr(e)) + return False + + def _publish_image(self, header, image, timestamp): + """Publish JPG image as a ROS message. + + :param header: The HTTP-like header read from the stream. + :type header: dict + :param image: The video frame in JPG. + :type image: :py:obj:`basestring` + :param timestamp: The time when the frame was captured (or its best estimation). + :type timestamp: :py:class:`rospy.Time` + """ + msg = CompressedImage() + msg.header.stamp = timestamp + msg.header.frame_id = self._axis._frame_id + msg.format = "jpeg" + msg.data = image + self._axis._video_publisher.publish(msg) + + def _publish_camera_info(self, header, image, timestamp): + """Publish camera info corresponding to the given image. + + :param header: The HTTP-like header read from the stream. + :type header: dict + :param image: The video frame in JPG. + :type image: :py:obj:`basestring` + :param timestamp: The time when the frame was captured (or its best estimation). + :type timestamp: :py:class:`rospy.Time` + """ + msg = self._axis._camera_info.getCameraInfo() + msg.header.stamp = timestamp + msg.header.frame_id = self._axis._frame_id + msg.width = self._axis._width + msg.height = self._axis._height + self._axis._camera_info_publisher.publish(msg) + + # BACKWARDS COMPATIBILITY LAYER + def authenticate(self): # is already done when connecting to VAPIX + """Deprecated.""" + pass + + def publishFramesContinuously(self): + """Deprecated.""" + self._publish_frames_until_error() + + def findBoundary(self): + """Deprecated.""" + VAPIX._find_boundary_in_stream(self.fp) + + def getImage(self): + """Deprecated.""" + self.getHeader() + self.getImageData() + + def getHeader(self): + """Deprecated.""" + self.header = VAPIX._get_image_header_from_stream(self.fp) + self.content_length = int(self.header['Content-Length']) + + def getImageData(self): + """Deprecated.""" + if self.content_length > 0: + self.img = VAPIX._get_image_data_from_stream(self.fp, self.content_length) + + def publishMsg(self): + """Deprecated.""" + self._publish_image(self.header, self.img, rospy.Time.now()) + + def publishCameraInfoMsg(self): + """Deprecated.""" + self._publish_camera_info(self.header, self.img, rospy.Time.now()) diff --git a/setup.py b/setup.py index 6317e60..e415b75 100644 --- a/setup.py +++ b/setup.py @@ -3,8 +3,10 @@ from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup -d = generate_distutils_setup( +setup_args = generate_distutils_setup( + packages=['axis_camera'], + package_dir={'': 'scripts'}, install_requires=['rospy', 'urllib2'], ) -setup(**d) +setup(**setup_args) diff --git a/srv/TakeSnapshot.srv b/srv/TakeSnapshot.srv new file mode 100644 index 0000000..19b4ad8 --- /dev/null +++ b/srv/TakeSnapshot.srv @@ -0,0 +1,2 @@ +--- +sensor_msgs/CompressedImage image \ No newline at end of file diff --git a/urdf/axis_214_PTZ.urdf b/urdf/axis_214_PTZ.urdf new file mode 100755 index 0000000..5d0bb58 --- /dev/null +++ b/urdf/axis_214_PTZ.urdf @@ -0,0 +1,88 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/urdf/axis_214_PTZ_standalone.xacro b/urdf/axis_214_PTZ_standalone.xacro new file mode 100755 index 0000000..8199353 --- /dev/null +++ b/urdf/axis_214_PTZ_standalone.xacro @@ -0,0 +1,13 @@ + + + + + + + + + + + + +