-
Notifications
You must be signed in to change notification settings - Fork 162
/
Copy pathSpinnaker.cfg
executable file
·318 lines (233 loc) · 23.8 KB
/
Spinnaker.cfg
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
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
#! /usr/bin/env python
'''
This code was developed by the National Robotics Engineering Center (NREC),
part of Carnegie Mellon University's Robotics Institute. Its development was
funded by DARPA under the LS3 program and submitted for public release
on June 7th, 2012. Release was granted on August, 21st 2012 with Distribution Statement A
(Approved for Public Release, Distribution Unlimited).
This software is released under a BSD license:
Copyright (c) 2012, National Robotics Engineering Center (NREC)
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 the National Robotics Engineering Center (NREC) 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 HOLDER 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.
'''
'''
@file Camera.cfg
@author Chad Rockey
@date July 11, 2011
@brief Interface to Point Grey cameras
@attention Copyright (C) 2011
@attention National Robotics Engineering Center
@attention Carnegie Mellon University
@attention Adapted from ROS Camera1394.cfg by Jack O' Quin
'''
#* Copyright (c) 2010, Jack O'Quin
#* All rights reserved. BSD.
#*
#* 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 the author nor the names of other
#* 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.
#***********************************************************
PACKAGE='spinnaker_camera_driver'
from dynamic_reconfigure.parameter_generator_catkin import *
class SensorLevels:
RECONFIGURE_RUNNING = 0
RECONFIGURE_STOP = 1
gen = ParameterGenerator()
# Name Type Reconfiguration level Description Default Min Max
gen.add("acquisition_frame_rate", double_t, SensorLevels.RECONFIGURE_RUNNING, "User controlled acquisition frame rate in Hertz (frames per second).", 10, 0, 120)
gen.add("acquisition_frame_rate_enable", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Enables manual (True) and automatic (False) control of the aquisition frame rate", False)
# Set Exposure
# Note: For the Auto Exposure feature, gain and/or exposure time must be set to Once or Continuous.
capture_modes = gen.enum([gen.const("AutoOff", str_t, "Off", ""),
gen.const("AutoOnce", str_t, "Once", ""),
gen.const("AutoContinuous", str_t, "Continuous", "")],
"Automatic mode: Off, Once, or Continuous.")
gen.add("exposure_mode", str_t, SensorLevels.RECONFIGURE_STOP, "Sets the operation mode of the Exposure (Timed or TriggerWidth).", "Timed")
gen.add("exposure_auto", str_t, SensorLevels.RECONFIGURE_RUNNING, "Sets the automatic exposure mode to: 'Off', 'Once' or 'Continuous'", "Continuous", edit_method=capture_modes)
gen.add("exposure_time", double_t, SensorLevels.RECONFIGURE_RUNNING, "Exposure time in microseconds when Exposure Mode is Timed and Exposure Auto is not Continuous.", 100.0, 0.0, 3000000.0)
gen.add("auto_exposure_time_upper_limit", double_t, SensorLevels.RECONFIGURE_RUNNING, "Upper Limit on Shutter Speed.", 5000, 0.0, 3000000.0)
# Gain Settings
gen.add("gain_selector", str_t, SensorLevels.RECONFIGURE_RUNNING, "Selects which gain to control. The All selection is a total amplification across all channels.", "All")
gen.add("auto_gain", str_t, SensorLevels.RECONFIGURE_RUNNING, "Gain state control. (Off, Once, Continuous)", "Continuous", edit_method=capture_modes)
gen.add("gain", double_t, SensorLevels.RECONFIGURE_RUNNING, "Controls the amplification of the video signal in dB.", 0, -10, 30)
# Pan and Tilt not in Spinnaker Driver
# gen.add("pan", int_t, SensorLevels.RECONFIGURE_RUNNING, "Controls camera pan.", 0, -1000, 1000)
# gen.add("tilt", int_t, SensorLevels.RECONFIGURE_RUNNING, "Controls camera tilt.", 0, -1000, 1000)
# Brightness = Black Level
gen.add("brightness", double_t, SensorLevels.RECONFIGURE_RUNNING, "Also known as Black level offset. Refers to the output of the camera when not illuminated.", 1.7, 0.0, 10.0)
gen.add("sharpening_enable", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Enables/disables the sharpening feature. Sharpening is disabled by default.", False)
gen.add("auto_sharpness", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Enables/disables the auto sharpening feature.", True)
gen.add("sharpness", double_t, SensorLevels.RECONFIGURE_RUNNING, "Controls the amount to sharpen a signal.", 1024.0, 0.0, 4095.0)
gen.add("sharpening_threshold", double_t, SensorLevels.RECONFIGURE_RUNNING, "Controls the minimum intensity gradient change to invoke sharpening. ", 0.1, 0.0, 0.25)
gen.add("saturation_enable", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Enables/disables Saturation adjustment..", False)
gen.add("saturation", double_t, SensorLevels.RECONFIGURE_RUNNING, "Saturation.", 100.0, 0.0, 399.0)
gen.add("gamma_enable", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Enables/disables gamma correction.", True)
gen.add("gamma", double_t, SensorLevels.RECONFIGURE_RUNNING, "Controls the gamma correction of pixel intensity.", 1.0, 0.5, 4.0)
# White Balance
gen.add("auto_white_balance", str_t, SensorLevels.RECONFIGURE_RUNNING, "White Balance compensates for color shifts caused by different lighting conditions.", "Off", edit_method=capture_modes)
gen.add("white_balance_blue_ratio", double_t, SensorLevels.RECONFIGURE_RUNNING, "White balance blue component.", 800, 0, 1023)
gen.add("white_balance_red_ratio", double_t, SensorLevels.RECONFIGURE_RUNNING, "White balance red component.", 550, 0, 1023)
# Image Format Control parameters
gen.add("image_format_roi_width", int_t, SensorLevels.RECONFIGURE_STOP, "Width of the image provided by the device (in pixels).", 0, 0, 65535)
gen.add("image_format_roi_height", int_t, SensorLevels.RECONFIGURE_STOP, "Height of the image provided by the device (in pixels).", 0, 0, 65535)
gen.add("image_format_x_offset", int_t, SensorLevels.RECONFIGURE_STOP, "Horizontal offset from the origin to the ROI (in pixels).", 0, 0, 65535)
gen.add("image_format_y_offset", int_t, SensorLevels.RECONFIGURE_STOP, "Vertical offset from the origin to the ROI (in pixels).", 0, 0, 65535)
gen.add("image_format_x_binning", int_t, SensorLevels.RECONFIGURE_STOP, "Horizontal Binning.", 1, 1, 8)
gen.add("image_format_y_binning", int_t, SensorLevels.RECONFIGURE_STOP, "Vertical Binning.", 1, 1, 8)
gen.add("image_format_x_decimation", int_t, SensorLevels.RECONFIGURE_STOP, "Horizontal Decimation.", 1, 1, 8)
gen.add("image_format_y_decimation", int_t, SensorLevels.RECONFIGURE_STOP, "Vertical Decimation.", 1, 1, 8)
gen.add("image_format_x_reverse", bool_t, SensorLevels.RECONFIGURE_STOP, "Horizontal Reverse.", False)
gen.add("image_format_y_reverse", bool_t, SensorLevels.RECONFIGURE_STOP, "Vertical Reverse.", False)
# Image Color Coding: Format of the pixel provided by the camera.
codings = gen.enum([gen.const("Mono8", str_t, "Mono8", ""),
gen.const("Mono16", str_t, "Mono16", ""),
gen.const("RGB8Packed", str_t, "RGB8Packed", ""),
gen.const("BayerGR8", str_t, "BayerGR8", ""),
gen.const("BayerRG8", str_t, "BayerRG8", ""),
gen.const("BayerGB8", str_t, "BayerGB8", ""),
gen.const("BayerBG8", str_t, "BayerBG8", ""),
gen.const("BayerGR16", str_t, "BayerGR16", ""),
gen.const("BayerRG16", str_t, "BayerRG16", ""),
gen.const("BayerGB16", str_t, "BayerGB16", ""),
gen.const("BayerBG16", str_t, "BayerBG16", ""),
gen.const("Mono12Packed", str_t, "Mono12Packed", ""),
gen.const("BayerGR12Packed", str_t, "BayerGR12Packed", ""),
gen.const("BayerRG12Packed", str_t, "BayerRG12Packed", ""),
gen.const("BayerGB12Packed", str_t, "BayerGB12Packed", ""),
gen.const("BayerBG12Packed", str_t, "BayerBG12Packed", ""),
gen.const("YUV411Packed", str_t, "YUV411Packed", ""),
gen.const("YUV422Packed", str_t, "YUV422Packed", ""),
gen.const("YUV444Packed", str_t, "YUV444Packed", ""),
gen.const("Mono12p", str_t, "Mono12p", ""),
gen.const("BayerGR12p", str_t, "BayerGR12p", ""),
gen.const("BayerRG12p", str_t, "BayerRG12p", ""),
gen.const("BayerGB12p", str_t, "BayerGB12p", ""),
gen.const("BayerBG12p", str_t, "BayerBG12p", ""),
gen.const("YCbCr8", str_t, "YCbCr8", ""),
gen.const("YCbCr422_8", str_t, "YCbCr422_8", ""),
gen.const("YCbCr411_8", str_t, "YCbCr411_8", ""),
gen.const("BGR8", str_t, "BGR8", ""),
gen.const("BGRa8", str_t, "BGRa8", "")],
"Image Color Coding: Format of the pixel provided by the camera.")
gen.add("image_format_color_coding", str_t, SensorLevels.RECONFIGURE_STOP, "Image Color coding", "Mono8", edit_method = codings)
gen.add("isp_enable", bool_t, SensorLevels.RECONFIGURE_STOP, "Controls whether the image processing core is used for optional pixel format mode", True)
# Trigger parameters
# enable_trigger specified by "TriggerMode" in Spinnaker: Controls whether or not trigger is active.
gen.add("enable_trigger", str_t, SensorLevels.RECONFIGURE_RUNNING, "Enable the external triggering mode.", "Off")
trigger_selector_options = gen.enum([gen.const("AcquisitionStart", str_t, "AcquisitionStart", ""),
gen.const("FrameStart", str_t, "FrameStart", ""),
gen.const("FrameBurstStart", str_t, "FrameBurstStart", "")],
"Trigger Types")
gen.add("trigger_selector", str_t, SensorLevels.RECONFIGURE_RUNNING, "Selects the type of trigger to configure.", "FrameStart", edit_method = trigger_selector_options)
# trigger_modes specified by "TriggerActivation" in Spinnaker: Specifies the activation mode of the trigger.
trigger_modes = gen.enum([gen.const("LevelLow", str_t, "LevelLow", ""),
gen.const("LevelHigh", str_t, "LevelHigh", ""),
gen.const("FallingEdge", str_t, "FallingEdge", ""),
gen.const("RisingEdge", str_t, "RisingEdge", ""),
gen.const("AnyEdge", str_t, "AnyEdge", "")],
"Trigger Activation Modes")
gen.add("trigger_activation_mode", str_t, SensorLevels.RECONFIGURE_RUNNING, "Trigger Activiation Modes", "FallingEdge", edit_method = trigger_modes)
trigger_sources = gen.enum([gen.const("Software", str_t, "Software", ""),
gen.const("Line0", str_t, "Line0", ""),
gen.const("Line1", str_t, "Line1", ""),
gen.const("Line2", str_t, "Line2", ""),
gen.const("Line3", str_t, "Line3", ""),
gen.const("UserOutput0", str_t, "UserOutput0", ""),
gen.const("UserOutput1", str_t, "UserOutput1", ""),
gen.const("UserOutput2", str_t, "UserOutput2", ""),
gen.const("UserOutput3", str_t, "UserOutput3", ""),
gen.const("Counter0Start", str_t, "Counter0Start", ""),
gen.const("Counter1Start", str_t, "Counter1Start", ""),
gen.const("Counter0End", str_t, "Counter0End", ""),
gen.const("Counter1End", str_t, "Counter1End", ""),
gen.const("LogicBlock0", str_t, "LogicBlock0", ""),
gen.const("LogicBlock1", str_t, "LogicBlock1", ""),
gen.const("Action0", str_t, "Action0", "")],
"Software and Hardware Trigger Sources")
# Trigger Source: Specifies the internal signal or physical input line to use as the trigger source.
gen.add("trigger_source", str_t, SensorLevels.RECONFIGURE_RUNNING, "Trigger Sources", "Line0", edit_method = trigger_sources)
# Trigger Overlap: Specifies the overlap mode of the trigger.
trigger_overlap_modes = gen.enum([gen.const("Off", str_t, "Off", ""),
gen.const("ReadOut", str_t, "ReadOut", ""),
gen.const("PreviousFrame", str_t, "PreviousFrame", "")],
"Trigger Overlap Modes")
gen.add("trigger_overlap_mode", str_t, SensorLevels.RECONFIGURE_RUNNING, "Trigger Overlap Modes", "ReadOut", edit_method = trigger_overlap_modes)
# gen.add("enable_trigger_delay", bool_t, SensorLevels.RECONFIGURE_RUNNING, "Whether Trigger Delay is active.", False)
# gen.add("trigger_delay", double_t, SensorLevels.RECONFIGURE_RUNNING, "The trigger delay to wait once triggered (in seconds).", 0.0, 0.0, 1.0)
# gen.add("trigger_parameter", int_t, SensorLevels.RECONFIGURE_RUNNING, "Trigger mode parameter. Varies based on mode.", 0, -32768, 32767)
line_sources = gen.enum([gen.const("LineSource_Off", str_t, "Off", ""),
gen.const("LineSource_Line0", str_t, "Line0", ""),
gen.const("LineSource_Line1", str_t, "Line1", ""),
gen.const("LineSource_Line2", str_t, "Line2", ""),
gen.const("LineSource_Line3", str_t, "Line3", ""),
gen.const("LineSource_UserOutput0", str_t, "UserOutput0", ""),
gen.const("LineSource_UserOutput1", str_t, "UserOutput1", ""),
gen.const("LineSource_UserOutput2", str_t, "UserOutput2", ""),
gen.const("LineSource_UserOutput3", str_t, "UserOutput3", ""),
gen.const("LineSource_Counter0Active", str_t, "Counter0Active", ""),
gen.const("LineSource_Counter1Active", str_t, "Counter1Active", ""),
gen.const("LineSource_LogicBlock0", str_t, "LogicBlock0", ""),
gen.const("LineSource_LogicBlock1", str_t, "LogicBlock1", ""),
gen.const("LineSource_ExposureActive", str_t, "ExposureActive", ""),
gen.const("LineSource_FrameTriggerWait", str_t, "FrameTriggerWait", ""),
gen.const("LineSource_SerialPort0", str_t, "SerialPort0", ""),
gen.const("LineSource_PPSSignal", str_t, "PPSSignal", ""),
gen.const("LineSource_AllPixel", str_t, "AllPixel", ""),
gen.const("LineSource_AnyPixel", str_t, "AnyPixel", "")],
"Selects which internal acquisition or I/O source signal to output on the selected line. LineMode must be Output")
gen.add("line_source", str_t, SensorLevels.RECONFIGURE_RUNNING, "Line Sources", "Off", edit_method = line_sources)
trigger_sources = gen.enum([gen.const("LineSelector_Line0", str_t, "Line0", ""),
gen.const("LineSelector_Line1", str_t, "Line1", ""),
gen.const("LineSelector_Line2", str_t, "Line2", ""),
gen.const("LineSelector_Line3", str_t, "Line3", "")],
"Selects the physical line (or pin) of the external device connector to configure.")
gen.add("line_selector", str_t, SensorLevels.RECONFIGURE_RUNNING, "Line Selector", "Line0", edit_method = trigger_sources)
line_modes = gen.enum([gen.const("Input", str_t, "Input", ""),
gen.const("Output", str_t, "Output", "")],
"Line Mode")
gen.add("line_mode", str_t, SensorLevels.RECONFIGURE_RUNNING, "Line Mode", "Input", edit_method = line_modes)
# Auto algorithm parameters
gen.add("auto_exposure_roi_offset_x", int_t, SensorLevels.RECONFIGURE_RUNNING, "Auto exposure ROI X offset.", 0, 0, 65535)
gen.add("auto_exposure_roi_offset_y", int_t, SensorLevels.RECONFIGURE_RUNNING, "Auto exposure ROI Y offset.", 0, 0, 65535)
gen.add("auto_exposure_roi_width", int_t, SensorLevels.RECONFIGURE_RUNNING, "Auto exposure ROI width.", 0, 0, 65535)
gen.add("auto_exposure_roi_height", int_t, SensorLevels.RECONFIGURE_RUNNING, "Auto exposure ROI height.", 0, 0, 65535)
auto_lighting_mode = gen.enum([
gen.const("Normal", str_t, "Normal", "Normal"),
gen.const("Frontlight", str_t, "Frontlight", "Front Lighting"),
gen.const("Backlight", str_t, "Backlight", "Back Lighting")
], "Auto algorithms lighting modes")
gen.add("auto_exposure_lighting_mode", str_t, SensorLevels.RECONFIGURE_RUNNING, "Auto exposure lighting mode.", "Normal", edit_method=auto_lighting_mode)
# GigE camera parameters
gen.add("gige_parameter_enable", bool_t, SensorLevels.RECONFIGURE_STOP, "GigE camera parameters enabled", False)
gen.add("device_link_throughput_limit", int_t, SensorLevels.RECONFIGURE_RUNNING, "Device link throughput limit", 14353165, 0)
gen.add("camera_packet_size", int_t, SensorLevels.RECONFIGURE_STOP, "GigE camera packet size", 1400, 0)
# Other
gen.add("time_offset", double_t, SensorLevels.RECONFIGURE_RUNNING, "Time offset to add to image time stamps.", 0.0, -5.0, 5.0)
exit(gen.generate(PACKAGE, "spinnaker_camera_driver", "Spinnaker"))