common_parameters.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 #*
3 #* Copyright (c) 2009, Willow Garage, Inc.
4 #* All rights reserved.
5 #*
6 #* Redistribution and use in source and binary forms, with or without
7 #* modification, are permitted provided that the following conditions
8 #* are met:
9 #*
10 #* * Redistributions of source code must retain the above copyright
11 #* notice, this list of conditions and the following disclaimer.
12 #* * Redistributions in binary form must reproduce the above
13 #* copyright notice, this list of conditions and the following
14 #* disclaimer in the documentation and/or other materials provided
15 #* with the distribution.
16 #* * Neither the name of the Willow Garage nor the names of its
17 #* contributors may be used to endorse or promote products derived
18 #* from this software without specific prior written permission.
19 #*
20 #* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 #* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 #* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 #* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 #* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 #* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 #* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 #* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 #* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 #* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 #* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 #* POSSIBILITY OF SUCH DAMAGE.
32 #***********************************************************
33 
34 # Author: Blaise Gassend
35 
36 # WGE100 camera configuration, non camera-specific settings.
37 
38 PACKAGE='wge100_camera'
39 
40 from driver_base.msg import SensorLevels
42 
43 def add_others(gen):
44  enum_register_set = gen.enum([
45  gen.const("PrimaryRegisterSet", int_t, 0, "The primary register set is always used."),
46  gen.const("AlternateRegisterSet", int_t, 1, "The alternate register set is always used."),
47  gen.const("Auto", int_t, 2, "The trigger signal selects which register set to use.")],
48  "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.")
49 
50  # Name Type Reconfiguration level Description Default Min Max
51  #gen.add("exit_on_fault", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Indicates if the driver should exit when an error occurs.", False)
52  gen.add("frame_id", str_t, SensorLevels.RECONFIGURE_RUNNING, "Sets the TF frame from which the camera is publishing.", "")
53  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)
54 
55  gen.add("width", int_t, SensorLevels.RECONFIGURE_CLOSE, "Number of pixels horizontally.", 640, 1, 752)
56  gen.add("height", int_t, SensorLevels.RECONFIGURE_CLOSE, "Number of pixels vertically.", 480, 1, 480)
57  gen.add("horizontal_binning", int_t, SensorLevels.RECONFIGURE_CLOSE, "Number of pixels to bin together horizontally.", 1, 1, 4)
58  gen.add("vertical_binning", int_t, SensorLevels.RECONFIGURE_CLOSE, "Number of pixels to bin together vertically.", 1, 1, 4)
59  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)
60  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)
61  gen.add("mirror_x", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Mirrors the image left to right.", False)
62  gen.add("mirror_y", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Mirrors the image top to bottom.", False)
63  gen.add("rotate_180", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Rotates the image 180 degrees. Acts in addition to the mirorr parameters", False)
64 
65  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)
66  gen.add("ext_trig", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Set camera to trigger from the external trigger input.", False)
67  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)
68  gen.add("trig_timestamp_topic", str_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the topic from which an externally trigged camera receives its trigger timestamps.", "")
69  gen.add("trig_rate", double_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the expected triggering rate in externally triggered mode.", 30, 1, 100)
70  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)
71 
72  gen.add("brightness", int_t, SensorLevels.RECONFIGURE_CLOSE, "The camera brightness for automatic gain/exposure.", 58, 1, 64)
73  gen.add("auto_black_level", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Enables the automatic black-level detection.", False)
74  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)
75  gen.add("black_level_step_size", int_t, SensorLevels.RECONFIGURE_CLOSE, "Maximum per-frame change in the auto black-level.", 2, 0, 31)
76  gen.add("black_level", int_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the black level.", 0, -127, 127)
77  gen.add("max_exposure", double_t, SensorLevels.RECONFIGURE_CLOSE, "Maximum exposure time in seconds in automatic exposure mode. Zero for automatic.", 0, 0, .1)
78 
79  gen.add("auto_exposure", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the camera exposure duration to automatic. Causes the exposure setting to be ignored.", True)
80  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)
81  gen.add("auto_gain", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Sets the analog gain to automatic. Causes the gain setting to be ignored.", True)
82  gen.add("gain", int_t, SensorLevels.RECONFIGURE_CLOSE, "The camera analog gain.", 32, 16, 127)
83  gen.add("companding", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Turns on companding (a non-linear intensity scaling to improve sensitivity in dark areas).", True)
84 
85  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)
86  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)
87  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)
88  gen.add("gain_alternate", int_t, SensorLevels.RECONFIGURE_CLOSE, "The alternate camera analog gain.", 32, 16, 127)
89  gen.add("companding_alternate", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Turns on companding for the alternate imager register set.", True)
90  gen.add("test_pattern", bool_t, SensorLevels.RECONFIGURE_CLOSE, "Turns on the camera's test pattern.", False)
91  gen.add("packet_debug", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Enable debug mode for dropped packets in diagnostics", False)


wge100_camera
Author(s): Blaise Gassend, Patrick Mihelich, Eric MacIntosh, David Palchak
autogenerated on Mon Jun 10 2019 15:44:15