-
Notifications
You must be signed in to change notification settings - Fork 43
/
Copy pathpico_flexx_driver.cfg
executable file
·41 lines (34 loc) · 3.11 KB
/
pico_flexx_driver.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
#!/usr/bin/env python
PACKAGE = "pico_flexx_driver"
from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
use_cases = gen.enum([ gen.const("MODE_9_5FPS_2000", int_t, 0, "8+1, 5 FPS, max exposure time 2000 micro seconds"),
gen.const("MODE_9_10FPS_1000", int_t, 1, "8+1, 10 FPS, max exposure time 1000 micro seconds"),
gen.const("MODE_9_15FPS_700", int_t, 2, "8+1, 15 FPS, max exposure time 700 micro seconds"),
gen.const("MODE_9_25FPS_450", int_t, 3, "8+1, 25 FPS, max exposure time 450 micro seconds"),
gen.const("MODE_5_35FPS_600", int_t, 4, "4+1, 35 FPS, max exposure time 600 micro seconds"),
gen.const("MODE_5_45FPS_500", int_t, 5, "4+1, 45 FPS, max exposure time 500 micro seconds"),
gen.const("MODE_MIXED_30_5", int_t, 6, "Mixed mode: 30/5 FPS, max exposure time 300/1300 micro seconds"),
gen.const("MODE_MIXED_50_5", int_t, 7, "Mixed mode: 50/5 FPS, max exposure time 250/1000 micro seconds"),
gen.const("Low_Noise_Extended",int_t, 8, "5 FPS, Low_Noise_Extended"),
gen.const("Fast_Acquisition", int_t, 9, "45 FPS, custom filter level")
], "possible use cases")
exposure_modes = gen.enum([ gen.const("MANUAL", int_t, 0, "Manual exposure mode"),
gen.const("AUTOMATIC", int_t, 1, "Automatic exposure mode")
], "Possible exposure modes")
# Royale allows to set different filter levels. Internally these represent
# different configurations of the processing pipeline.
filter_levels = gen.enum([ gen.const("Off", int_t, 0, "Turn off all filtering of the data (validation will still be enabled)"),
gen.const("Legacy", int_t, 200, "Standard settings for older cameras"),
gen.const("Full", int_t, 255, "Enable all filters that are available for this camera"),
gen.const("Custom", int_t, 256, "Value returned by getFilterLevel if the processing parameters differ from all of the presets")
], "Possible filter levels")
gen.add("use_case", int_t, 0x01, "Use cases for the sensor", 0, 0, 9, edit_method=use_cases)
gen.add("exposure_mode", int_t, 0x02, "Exposure mode for the sensor", 0, 0, 1, edit_method=exposure_modes)
gen.add("exposure_mode_stream2", int_t, 0x04, "Exposure mode for the sensor (stream 2)", 0, 0, 1, edit_method=exposure_modes)
gen.add("exposure_time", int_t, 0x08, "Exposure time", 1000, 1, 2000)
gen.add("exposure_time_stream2", int_t, 0x10, "Exposure time (stream 2)", 1000, 1, 2000)
gen.add("max_noise", double_t, 0x20, "Max allowed noise", 0.07, 0.0, 0.1)
gen.add("range_factor", double_t, 0x40, "Range of factor times standard deviation arround mean", 2.0, 0.0, 7.0)
gen.add("filter_level", int_t, 0x80, "Filter level", 200, 0, 256, edit_method=filter_levels)
exit(gen.generate(PACKAGE, "pico_flexx_driver", "pico_flexx_driver"))