forked from srv/avt_vimba_camera
-
Notifications
You must be signed in to change notification settings - Fork 43
/
Copy pathmono_camera.launch
159 lines (142 loc) · 7.69 KB
/
mono_camera.launch
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
<launch>
<!-- Driver parameters, these parameters affect the way the ROS driver works -->
<arg name="name" default="camera" doc="The name of the camera"/>
<arg name="ip" default="" doc="The IP for the camera to connect to"/>
<arg name="guid" default="" doc="The GUID for the camera to connect to"/>
<arg name="frame_id" default="$(arg name)" doc="The frame id of the camera"/>
<arg name="use_measurement_time" default="false" doc="Use the measurement time from the camera"/>
<arg name="ptp_offset" default="-37" doc="Offset to add to the timestamp from the camera (s).
Useful for converting from TAI to UTC time. Only applies if use_measurement_time is true"/>
<arg name="camera_info_url" default="file://$(find avt_vimba_camera)/calibrations/calibration_example.yaml"/>
<arg name="print_all_features" default="false" doc="Show all camera features on the console during startup"/>
<arg name="image_proc" default="false" doc="Launch image_proc with driver"/>
<!-- Camera parameters, these parameters are used to configure the AVT camera upon startup -->
<!-- See the cfg/AvtVimbaCamera.cfg file for documentation -->
<!-- Acquisition -->
<arg name="acquisition_mode" default="Continuous"/>
<arg name="acquisition_rate" default="10"/>
<arg name="acquisition_rate_enable" default="False"/>
<!-- Trigger -->
<arg name="trigger_source" default="FixedRate"/>
<arg name="trigger_mode" default="On"/>
<arg name="trigger_selector" default="FrameStart"/>
<arg name="trigger_activation" default="RisingEdge"/>
<arg name="trigger_delay" default="0.0"/>
<!-- Exposure -->
<arg name="exposure" default="50000"/>
<arg name="exposure_auto" default="Continuous"/>
<arg name="exposure_auto_alg" default="FitRange"/>
<arg name="exposure_auto_tol" default="5"/>
<arg name="exposure_auto_max" default="50000"/>
<arg name="exposure_auto_min" default="50000"/>
<arg name="exposure_auto_outliers" default="50000"/>
<arg name="exposure_auto_rate" default="50000"/>
<arg name="exposure_auto_target" default="50000"/>
<!-- Gain -->
<arg name="gain" default="0"/>
<arg name="gain_auto" default="Continuous"/>
<arg name="gain_auto_adjust_tol" default="5"/>
<arg name="gain_auto_max" default="32"/>
<arg name="gain_auto_min" default="0"/>
<arg name="gain_auto_outliers" default="0"/>
<arg name="gain_auto_rate" default="50"/>
<arg name="gain_auto_target" default="50"/>
<!-- White Balance -->
<arg name="balance_ratio_abs" default="1.0"/>
<arg name="balance_ratio_selector" default="Red"/>
<arg name="whitebalance_auto" default="Continuous"/>
<arg name="whitebalance_auto_tol" default="5"/>
<arg name="whitebalance_auto_rate" default="100"/>
<!-- Binning and Decimation -->
<arg name="binning_x" default="1"/>
<arg name="binning_y" default="1"/>
<arg name="decimation_x" default="1"/>
<arg name="decimation_y" default="1"/>
<!-- ROI -->
<arg name="width" default="1920"/>
<arg name="height" default="1440"/>
<arg name="offset_x" default="0"/>
<arg name="offset_y" default="0"/>
<!-- Pixel Format -->
<arg name="pixel_format" default="BayerRG8"/>
<!-- Bandwidth -->
<arg name="stream_bytes_per_second" default="45000000"/>
<!-- PTP Synchronization -->
<arg name="ptp_mode" default="Off"/>
<!-- GPIO -->
<arg name="sync_in_selector" default="SyncIn1"/>
<arg name="sync_out_polarity" default="Normal"/>
<arg name="sync_out_selector" default="SyncOut1"/>
<arg name="sync_out_source" default="GPO"/>
<!-- USB GPIO -->
<arg name="line_selector" default="Line0"/>
<arg name="line_mode" default="Input"/>
<!-- Iris -->
<arg name="iris_auto_target" default="50"/>
<arg name="iris_mode" default="Continuous"/>
<arg name="iris_video_level_min" default="110"/>
<arg name="iris_video_level_max" default="110"/>
<group if="$(arg image_proc)" ns="$(arg name)">
<node name="image_proc" pkg="image_proc" type="image_proc"/>
</group>
<node name="$(arg name)" pkg="avt_vimba_camera" type="mono_camera_node" output="screen">
<param name="ip" value="$(arg ip)"/>
<param name="guid" value="$(arg guid)"/>
<param name="frame_id" value="$(arg frame_id)"/>
<param name="use_measurement_time" value="$(arg use_measurement_time)"/>
<param name="ptp_offset" value="$(arg ptp_offset)"/>
<param name="camera_info_url" value="$(arg camera_info_url)"/>
<param name="print_all_features" value="$(arg print_all_features)"/>
<param name="acquisition_mode" value="$(arg acquisition_mode)"/>
<param name="acquisition_rate" value="$(arg acquisition_rate)"/>
<param name="acquisition_rate_enable" value="$(arg acquisition_rate_enable)"/>
<param name="trigger_source" value="$(arg trigger_source)"/>
<param name="trigger_mode" value="$(arg trigger_mode)"/>
<param name="trigger_selector" value="$(arg trigger_selector)"/>
<param name="trigger_activation" value="$(arg trigger_activation)"/>
<param name="trigger_delay" value="$(arg trigger_delay)"/>
<param name="exposure" value="$(arg exposure)"/>
<param name="exposure_auto" value="$(arg exposure_auto)"/>
<param name="exposure_auto_alg" value="$(arg exposure_auto_alg)"/>
<param name="exposure_auto_tol" value="$(arg exposure_auto_tol)"/>
<param name="exposure_auto_max" value="$(arg exposure_auto_max)"/>
<param name="exposure_auto_min" value="$(arg exposure_auto_min)"/>
<param name="exposure_auto_outliers" value="$(arg exposure_auto_outliers)"/>
<param name="exposure_auto_rate" value="$(arg exposure_auto_rate)"/>
<param name="exposure_auto_target" value="$(arg exposure_auto_target)"/>
<param name="gain" value="$(arg gain)"/>
<param name="gain_auto" value="$(arg gain_auto)"/>
<param name="gain_auto_adjust_tol" value="$(arg gain_auto_adjust_tol)"/>
<param name="gain_auto_max" value="$(arg gain_auto_max)"/>
<param name="gain_auto_min" value="$(arg gain_auto_min)"/>
<param name="gain_auto_outliers" value="$(arg gain_auto_outliers)"/>
<param name="gain_auto_rate" value="$(arg gain_auto_rate)"/>
<param name="gain_auto_target" value="$(arg gain_auto_target)"/>
<param name="balance_ratio_abs" value="$(arg balance_ratio_abs)"/>
<param name="balance_ratio_selector" value="$(arg balance_ratio_selector)"/>
<param name="whitebalance_auto" value="$(arg whitebalance_auto)"/>
<param name="whitebalance_auto_tol" value="$(arg whitebalance_auto_tol)"/>
<param name="whitebalance_auto_rate" value="$(arg whitebalance_auto_rate)"/>
<param name="binning_x" value="$(arg binning_x)"/>
<param name="binning_y" value="$(arg binning_y)"/>
<param name="decimation_x" value="$(arg decimation_x)"/>
<param name="decimation_y" value="$(arg decimation_y)"/>
<param name="width" value="$(arg width)"/>
<param name="height" value="$(arg height)"/>
<param name="offset_x" value="$(arg offset_x)"/>
<param name="offset_y" value="$(arg offset_y)"/>
<param name="pixel_format" value="$(arg pixel_format)"/>
<param name="stream_bytes_per_second" value="$(arg stream_bytes_per_second)"/>
<param name="ptp_mode" value="$(arg ptp_mode)"/>
<param name="sync_in_selector" value="$(arg sync_in_selector)"/>
<param name="sync_out_polarity" value="$(arg sync_out_polarity)"/>
<param name="sync_out_selector" value="$(arg sync_out_selector)"/>
<param name="sync_out_source" value="$(arg sync_out_source)"/>
<param name="line_selector" value="$(arg line_selector)"/>
<param name="line_mode" value="$(arg line_mode)"/>
<param name="iris_auto_target" value="$(arg iris_auto_target)"/>
<param name="iris_mode" value="$(arg iris_mode)"/>
<param name="iris_video_level_min" value="$(arg iris_video_level_min)"/>
<param name="iris_video_level_max" value="$(arg iris_video_level_max)"/>
</node>
</launch>