UVCCamera.cfg 5.94 KB
Newer Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
#! /usr/bin/env python
# Derived from camera1394 cfg

PACKAGE='libuvc_camera'
import roslib; roslib.load_manifest(PACKAGE)

from dynamic_reconfigure.parameter_generator import *
from driver_base.msg import SensorLevels

gen = ParameterGenerator()

#       Name, Type, Reconfiguration level, Description, Default, Min, Max

gen.add("vendor", str_t, SensorLevels.RECONFIGURE_CLOSE,
        "Vendor ID, hex digits (use camera of any vendor if null).",
        "")

gen.add("product", str_t, SensorLevels.RECONFIGURE_CLOSE,
        "Product ID, hex digits (use camera of any model if null).",
        "")

gen.add("serial", str_t, SensorLevels.RECONFIGURE_CLOSE,
        "Serial number, arbitrary string (use camera of any serial number if null).",
        "")

gen.add("index", int_t, SensorLevels.RECONFIGURE_CLOSE,
        "Index into the list of cameras that match the above parameters.",
        0)

gen.add("width", int_t, SensorLevels.RECONFIGURE_CLOSE,
        "Image width.", 640)

gen.add("height", int_t, SensorLevels.RECONFIGURE_CLOSE,
        "Image height.", 480)

gen.add("frame_rate", double_t, SensorLevels.RECONFIGURE_CLOSE,
        "Camera speed, frames per second.", 15.0, 0.1, 1000.0)

# TODO: video mode -- uncompressed, yuyv, uyvy, rgb, compressed, jpeg, ...

gen.add("frame_id", str_t, SensorLevels.RECONFIGURE_RUNNING,
        "ROS tf frame of reference, resolved with tf_prefix unless absolute.",
        "camera")

# Camera Terminal controls

scanning_modes = gen.enum([gen.const("Interlaced", int_t, 0, ""),
                           gen.const("Progressive", int_t, 1, "")],
                          "Scanning modes")

gen.add("scanning_mode", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Scanning mode.", 0, 0, 1,
        edit_method = scanning_modes)

auto_exposure_modes = gen.enum([gen.const("Manual", int_t, 0, "Manual exposure, manual iris"),
                                gen.const("Auto", int_t, 1, "Auto exposure, auto iris"),
                                gen.const("Shutter_Priority", int_t, 2, "manual exposure, auto iris"),
                                gen.const("Aperture_Priority", int_t, 3, "auto exposure, manual iris")],
                               "Auto-exposure modes")

gen.add("auto_exposure", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Auto exposure mode.",
        1, 0, 3, edit_method = auto_exposure_modes)

gen.add("auto_exposure_priority", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "In auto mode or shutter priority mode, allow the device to vary frame rate.",
        0, 0, 1)

gen.add("exposure_absolute", double_t, SensorLevels.RECONFIGURE_RUNNING,
        "Length of exposure, seconds.", 0., 0.0001, 10.0)

# TODO: relative exposure time

gen.add("iris_absolute", double_t, SensorLevels.RECONFIGURE_RUNNING,
        "Aperture, f.", 0., 0., 655.35)

# TODO: relative iris

gen.add("auto_focus", bool_t, SensorLevels.RECONFIGURE_RUNNING,
        "Maintain focus automatically.", False)

gen.add("focus_absolute", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Absolute focal distance, millimeters.", 0, 0, 65536)

# TODO: relative focus

# TODO: zoom

gen.add("pan_absolute", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Pan (clockwise), arc seconds.", 0, -180*3600, 180*3600)

gen.add("tilt_absolute", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Tilt (up), arc seconds.", 0, -180*3600, 180*3600)

# TODO: relative pan/tilt

gen.add("roll_absolute", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Roll (clockwise), degrees.", 0, -180, 180)

# TODO: relative roll

gen.add("privacy", bool_t, SensorLevels.RECONFIGURE_RUNNING,
        "Image capture disabled.", False)

# Processing Unit controls

gen.add("backlight_compensation", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Backlight compensation, device-dependent (zero for none, increasing compensation above zero).",
        0, 0, 65536)


gen.add("brightness", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Brightness, device dependent.", 0, -32768, 32767)

gen.add("contrast", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Contrast, device dependent.", 0, -32768, 32767)

gen.add("gain", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Gain, device dependent.", 0, 0, 65536)

power_line_frequency_modes = gen.enum([gen.const("Disabled", int_t, 0, "Disabled"),
                                       gen.const("Freq_50", int_t, 1, "50 Hz"),
                                       gen.const("Freq_60", int_t, 1, "60 Hz")],
                                      "Power line frequency modes")

gen.add("power_line_frequency", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Power line frequency anti-flicker processing.",
        0, 0, 2,
        edit_method = power_line_frequency_modes)

gen.add("auto_hue", bool_t, SensorLevels.RECONFIGURE_RUNNING,
        "Automatic hue control.", False)

gen.add("hue", double_t, SensorLevels.RECONFIGURE_RUNNING,
        "Hue, degrees.", 0., -180., 180.)

gen.add("saturation", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Saturation, device dependent (zero for grayscale).", 0, 0, 65536)

gen.add("sharpness", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "Image sharpness, device dependent.",
        0, 0, 65536)

# TODO: check range definition
gen.add("gamma", double_t, SensorLevels.RECONFIGURE_RUNNING,
        "Gamma.", 1.0, 0.01, 5.0)

gen.add("auto_white_balance", bool_t, SensorLevels.RECONFIGURE_RUNNING,
        "Automatic white balance.", False)

gen.add("white_balance_temperature", int_t, SensorLevels.RECONFIGURE_RUNNING,
        "White balance temperature, degrees.", 0, 0, 65536)

gen.add("white_balance_BU", double_t, SensorLevels.RECONFIGURE_RUNNING,
        "Blue or U component of white balance, device-dependent.",
        0, 0, 65536)

gen.add("white_balance_RV", double_t, SensorLevels.RECONFIGURE_RUNNING,
        "Red or V component of white balance, device-dependent.",
        0, 0, 65536)

# TODO: digital multiplier {,limit}

# TODO: analog video standard, analog video lock

exit(gen.generate(PACKAGE, "libuvc_camera", "UVCCamera"))