$search
00001 #! /usr/bin/env python 00002 #* 00003 #* Copyright (c) 2009, Willow Garage, Inc. 00004 #* All rights reserved. 00005 #* 00006 #* Redistribution and use in source and binary forms, with or without 00007 #* modification, are permitted provided that the following conditions 00008 #* are met: 00009 #* 00010 #* * Redistributions of source code must retain the above copyright 00011 #* notice, this list of conditions and the following disclaimer. 00012 #* * Redistributions in binary form must reproduce the above 00013 #* copyright notice, this list of conditions and the following 00014 #* disclaimer in the documentation and/or other materials provided 00015 #* with the distribution. 00016 #* * Neither the name of the Willow Garage nor the names of its 00017 #* contributors may be used to endorse or promote products derived 00018 #* from this software without specific prior written permission. 00019 #* 00020 #* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 #* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 #* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 #* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 #* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 #* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 #* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 #* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 #* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 #* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 #* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 #* POSSIBILITY OF SUCH DAMAGE. 00032 #*********************************************************** 00033 00034 # Author: Blaise Gassend 00035 00036 # WGE100 camera configuration, non camera-specific settings. 00037 00038 PACKAGE='wge100_camera' 00039 import roslib; roslib.load_manifest(PACKAGE) 00040 00041 from driver_base.msg import SensorLevels 00042 from dynamic_reconfigure.parameter_generator import * 00043 00044 def add_others(gen): 00045 enum_register_set = gen.enum([ 00046 gen.const("PrimaryRegisterSet", int_t, 0, "The primary register set is always used."), 00047 gen.const("AlternateRegisterSet", int_t, 1, "The alternate register set is always used."), 00048 gen.const("Auto", int_t, 2, "The trigger signal selects which register set to use.")], 00049 "Some wge100 cameras have two register sets. You can chose either set, or have the trigger signal select one of the sets. The camera images will go to camera or camera_alternate depending on which register set is active.") 00050 00051 # Name Type Reconfiguration level Description Default Min Max 00052 #gen.add("exit_on_fault", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Indicates if the driver should exit when an error occurs.", False) 00053 gen.add("frame_id", str_t, SensorLevels.RECONFIGURE_RUNNING, "Sets the TF frame from which the camera is publishing.", "") 00054 gen.add("register_set", int_t, SensorLevels.RECONFIGURE_CLOSE, "Select the register set to work with. In auto mode, an extra pulse on the trigger signal indicates that the alternate set should be used.", 0, 0, 3, enum_register_set) 00055 00056 gen.add("width", int_t, SensorLevels.RECONFIGURE_CLOSE, "Number of pixels horizontally.", 640, 1, 752) 00057 gen.add("height", int_t, SensorLevels.RECONFIGURE_CLOSE, "Number of pixels vertically.", 480, 1, 480) 00058 gen.add("horizontal_binning", int_t, SensorLevels.RECONFIGURE_CLOSE, "Number of pixels to bin together horizontally.", 1, 1, 4) 00059 gen.add("vertical_binning", int_t, SensorLevels.RECONFIGURE_CLOSE, "Number of pixels to bin together vertically.", 1, 1, 4) 00060 gen.add("x_offset", int_t, SensorLevels.RECONFIGURE_CLOSE, "Horizontal offset between the center of the image and the center of the imager in pixels.", 0, 0, 752) 00061 gen.add("y_offset", int_t, SensorLevels.RECONFIGURE_CLOSE, "Vertical offset between the center of the image and the center of the imager in pixels.", 0, 0, 480) 00062 gen.add("mirror_x", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Mirrors the image left to right.", False) 00063 gen.add("mirror_y", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Mirrors the image top to bottom.", False) 00064 gen.add("rotate_180", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Rotates the image 180 degrees. Acts in addition to the mirorr parameters", False) 00065 00066 gen.add("imager_rate", double_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the frame rate of the imager. In externally triggered mode this must be more than trig_rate", 30, 1, 100) 00067 gen.add("ext_trig", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Set camera to trigger from the external trigger input.", False) 00068 gen.add("rising_edge_trig", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Indicates that the camera should trigger on rising edges (as opposed to falling edges).", True) 00069 gen.add("trig_timestamp_topic", str_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the topic from which an externally trigged camera receives its trigger timestamps.", "") 00070 gen.add("trig_rate", double_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the expected triggering rate in externally triggered mode.", 30, 1, 100) 00071 gen.add("first_packet_offset", double_t, SensorLevels.RECONFIGURE_RUNNING, "Offset between the end of exposure and the minimal arrival time for the first frame packet. Only used when using internal triggering.", 0.0025, 0, .02) 00072 00073 gen.add("brightness", int_t, SensorLevels.RECONFIGURE_CLOSE, "The camera brightness for automatic gain/exposure.", 58, 1, 64) 00074 gen.add("auto_black_level", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Enables the automatic black-level detection.", False) 00075 gen.add("black_level_filter_length", int_t, SensorLevels.RECONFIGURE_CLOSE, "Base 2 logarithm of the number of frames the black-level algorithm should average over.", 4, 0, 7) 00076 gen.add("black_level_step_size", int_t, SensorLevels.RECONFIGURE_CLOSE, "Maximum per-frame change in the auto black-level.", 2, 0, 31) 00077 gen.add("black_level", int_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the black level.", 0, -127, 127) 00078 gen.add("max_exposure", double_t, SensorLevels.RECONFIGURE_CLOSE, "Maximum exposure time in seconds in automatic exposure mode. Zero for automatic.", 0, 0, .1) 00079 00080 gen.add("auto_exposure", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the camera exposure duration to automatic. Causes the exposure setting to be ignored.", True) 00081 gen.add("exposure", double_t, SensorLevels.RECONFIGURE_CLOSE, "Maximum camera exposure time in seconds. The valid range depends on the video mode.", 0.01, 0, 0.1) 00082 gen.add("auto_gain", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the analog gain to automatic. Causes the gain setting to be ignored.", True) 00083 gen.add("gain", int_t, SensorLevels.RECONFIGURE_CLOSE, "The camera analog gain.", 32, 16, 127) 00084 gen.add("companding", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Turns on companding (a non-linear intensity scaling to improve sensitivity in dark areas).", True) 00085 00086 gen.add("auto_exposure_alternate", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the alternate camera exposure duration to automatic. Causes the exposure_alternate setting to be ignored.", True) 00087 gen.add("exposure_alternate", double_t, SensorLevels.RECONFIGURE_CLOSE, "Alternate camera exposure in seconds. The valid range depends on the video mode.", 0.01, 0, .1) 00088 gen.add("auto_gain_alternate", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the alternate analog gain to automatic. Causes the gain_alternate setting to be ignored.", True) 00089 gen.add("gain_alternate", int_t, SensorLevels.RECONFIGURE_CLOSE, "The alternate camera analog gain.", 32, 16, 127) 00090 gen.add("companding_alternate", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Turns on companding for the alternate imager register set.", True) 00091 gen.add("test_pattern", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Turns on the camera's test pattern.", False) 00092 gen.add("packet_debug", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Enable debug mode for dropped packets in diagnostics", False)