-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathxiCam_config.yaml
91 lines (73 loc) · 3.74 KB
/
xiCam_config.yaml
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
ximea_cam_node:
ros__parameters:
####################
# General Configuration Parameters Go Here!
####################
# directory to save images (make sure that directory exists and that it is an absolute path).
image_directory: "/home/dev/" # must be absolute path, not relative path (i.e. '~')
# save images to the disk
save_disk: false
# save images on trigger (calibration only)
calib_mode: false
#########################
# Diagnostics Parameters
#########################
enable_diagnostics: true
data_age_max: 0.1
pub_frequency: 10.0
pub_frequency_tolerance: 1.0
#########################################
# Camera Configuration Parameters Go Here!
##########################################
# image_transport compressed image parameters
image_transport_compressed_format: "png"
image_transport_compressed_jpeg_quality: 100
image_transport_compressed_png_level: 5
# colour format
format: "XI_MONO8" # Recommended to set to RAW for ARM processors and do offline processing later
# some options: mono8, rgb24, raw8
# triggering (0 - none, 1 - software trigger (NOT IMPLMENTED YET),
# 2 - hardware trigger)
cam_trigger_mode: 0
hw_trigger_edge: 0 # if hw trigger, 0/1 = rising/falling edge trigger
# for camera frame rate
frame_rate_control: true # enable or disable frame razte control
# (works if no triggering is enabled)
frame_rate_set: 120 # for trigger mode, fps limiter (0 for none)
img_capture_timeout: 1000 # timeout in milliseconds for xiGetImage()
# exposure settings
auto_exposure: true # auto exposure on or off
exposure_time: 3000 # manual exposure time in microseconds
manual_gain: 9.0 # manual exposure gain
auto_exposure_priority: 0.8 # auto exposure to gain ratio (1 = use only exposure)
auto_time_limit: 30000 # auto exposure time limit in microseconds
auto_gain_limit: 2.0 # auto exposure gain limit
# camera coloring
# white balance mode: 0 - none, 1 - use coefficients, 2 = auto
white_balance_mode: 2
white_balance_coef_red: 3.0 # white balance red coefficient (0 to 8)
white_balance_coef_green: 0.0 # white balance green coefficient (0 to 8)
white_balance_coef_blue: 4.0 # white balance blue coefficient (0 to 8)
# region of interest
roi_left: 384 # top left corner in pixels
roi_top: 184
roi_width: 1280 # width height in pixels (2048)
roi_height: 720 # up to (1088)
#roi_left: 0 # top left corner in pixels
#roi_top: 0
#roi_width: 2048 # width height in pixels (2048)
#roi_height: 1088 # up to (1088)
# CV resizing
# alternative to roi, maintains FOV with an expected performance tradeoff
cv_resize_enable: false
cv_height: 512
cv_width: 640
# CV inverting for calibration purposes
cv_invert_enable: false
# lens control -> Only works if lens_mode is set to 1 (XI_ON)
# lens_mode: 0 #XI_PRM_LENS_MODE or "lens_mode", 1 to enable lens control, else 0
# lens_aperture_value: 0.0 #XI_PRM_LENS_APERTURE_VALUE or "lens_aperture_value"
# lens_aperture_index: 0 #XI_PRM_LENS_APERTURE_INDEX or "lens_aperture_index"
# lens_focus_movement_value: 0 #XI_PRM_LENS_FOCUS_MOVEMENT_VALUE or "lens_focus_movement_value"
# lens_focus_move: 0 #XI_PRM_LENS_FOCUS_MOVE or "lens_focus_move"
# lens_focal_length: 0 #XI_PRM_LENS_FOCAL_LENGTH or "lens_focal_length