-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathright_camera.launch.txt
109 lines (85 loc) · 4.89 KB
/
right_camera.launch.txt
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
<launch>
<arg name="camera_name" default="right_camera"/>
<arg name="camera_serial" default="18480369"/>
<arg name="calibrated" default="1"/>
<arg name="calibration_date" default="2022_01_22"/>
<arg name="frame_id" default="$(arg camera_name)"/>
<arg name="frame_rate" default="30"/>
<arg name="video_mode" default="format7_mode0"/>
<arg name="format7_color_coding" default="rgb8"/>
<arg name="auto_packet_size" default="True"/>
<arg name="packet_delay" default="1000"/>
<arg name="packet_size" default="1400"/>
<arg name="format7_roi_width" default="1288"/>
<arg name="format7_roi_height" default="964"/>
<arg name="format7_x_offset" default="0"/>
<arg name="format7_y_offset" default="0"/>
<arg name="enable_trigger" default="False"/>
<arg name="trigger_mode" default="mode0"/>
<arg name="trigger_source" default="0"/>
<arg name="trigger_polarity" default="1"/>
<arg name="auto_exposure" default="True"/>
<arg name="exposure" default="1.35"/>
<arg name="auto_shutter" default="True"/>
<arg name="shutter_speed" default="0.1"/>
<arg name="auto_gain" default="True"/>
<arg name="gain" default="-2"/>
<arg name="pan" default="0"/>
<arg name="tilt" default="0"/>
<arg name="brightness" default="0.0"/>
<arg name="gamma" default="1.8"/> <!-- default: 1.0 -->
<arg name="auto_white_balance" default="True"/>
<arg name="white_balance_blue" default="800"/>
<arg name="white_balance_red" default="550"/>
<group ns="$(arg camera_name)">
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager"/>
<node pkg="nodelet" type="nodelet" name="camera_nodelet" args="load spinnaker_camera_driver/SpinnakerCameraNodeletf camera_nodelet_manager">
<param name="serial" value="$(arg camera_serial)"/>
<param name="frame_id" value="$(arg frame_id)"/>
<param name="frame_rate" value="$(arg frame_rate)"/>
<param name="video_mode" value="$(arg video_mode)"/>
<param name="format7_color_coding" value="$(arg format7_color_coding)"/>
<param name="auto_packet_size" value="$(arg auto_packet_size)"/>
<param name="packet_delay" value="$(arg packet_delay)"/><!-- 1000, 650 -->
<param name="packet_size" value="$(arg packet_size)"/><!-- 1400, 900 -->
<param name="format7_roi_width" value="$(arg format7_roi_width)"/><!-- 1024 -->
<param name="format7_roi_height" value="$(arg format7_roi_height)"/><!-- 768 -->
<param name="format7_x_offset" value="$(arg format7_x_offset)"/><!-- 132 -->
<param name="format7_y_offset" value="$(arg format7_y_offset)"/><!-- 96 -->
<param name="enable_trigger" value="$(arg enable_trigger)"/>
<param name="trigger_mode" value="$(arg trigger_mode)"/>
<param name="trigger_source" value="$(arg trigger_source)"/>
<param name="trigger_polarity" value="$(arg trigger_polarity)"/>
<!-- Allow the camera to automatically change exposure (Combined Gain, Iris & Shutter control) / Default: True -->
<param name="auto_exposure" value="$(arg auto_exposure)"/>
<!-- Auto exposure value (like contrast) / Default: 1.35 / Range: -10.0 -> 10.0 -->
<param name="exposure" value="$(arg exposure)"/>
<!-- Shutter control state / Default: True -->
<param name="auto_shutter" value="$(arg auto_shutter)"/>
<!-- Auto exposure value (like contrast) / Default: 0.03 / Range: 0.0 -> 1.0 -->
<param name="shutter_speed" value="$(arg shutter_speed)"/><!-- Last: 0.005 Works: 0.001 -->
<!-- Gain control state / Default: True -->
<param name="auto_gain" value="$(arg auto_gain)"/>
<!-- Relative circuit gain / Default: 0 / Range: -10 -> 30 -->
<param name="gain" value="$(arg gain)"/>
<!-- Controls camera pan / Default: 0 / Range: -1000 -> 1000 -->
<param name="pan" value="$(arg pan)"/>
<!-- Controls camera tilt / Default: 0 / Range: -1000 -> 1000 -->
<param name="tilt" value="$(arg tilt)"/>
<!-- Black level offset / Default: 0.0 / Range: 0.0 -> 10.0 -->
<param name="brightness" value="$(arg brightness)"/><!-- 5.0 -->
<!-- Gamma expansion exponent / Default: 1.0 / Range: 0.5 -> 4.0 -->
<param name="gamma" value="$(arg gamma)"/>
<!-- Automatically change white balance / Default: True -->
<param name="auto_white_balance" value="$(arg auto_white_balance)"/>
<!-- White balance blue component / Default: 800 / Range: 0 -> 1023 -->
<param name="white_balance_blue" value="$(arg white_balance_blue)"/>
<!-- White balance red component / Default: 550 / Range: 0 -> 1023 -->
<param name="white_balance_red" value="$(arg white_balance_red)"/>
<!-- Use the camera_calibration package to create this file -->
<param name="camera_info_url" if="$(arg calibrated)" value="file://$(env HOME)/catkin_ws/src/AVT_Year1/calibration/cameras/$(arg calibration_date)/$(arg camera_name).yaml"/>
</node>
<node pkg="image_proc" type="image_proc" name="image_proc"/>
</group>
<!--<node pkg="image_view" type="image_view" name="$(arg camera_name)" args="image:=/$(arg camera_name)/image_raw compressed"/>-->
</launch>