-
Notifications
You must be signed in to change notification settings - Fork 90
/
Copy pathacquisition.launch
72 lines (63 loc) · 5.44 KB
/
acquisition.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
<launch>
<!-- configure console output verbosity mode:debug_console.conf or std_console.conf -->
<env name="ROSCONSOLE_CONFIG_FILE" value="$(find spinnaker_sdk_camera_driver)/cfg/std_console.conf"/>
<!-- acquisition spinnaker params-->
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
<arg name="external_trigger" default="false" doc="External trigger (No camera is master)"/>
<arg name="gain" default="0" doc="Gain setting. Gain should be positive (full range - 0 - 18 dB for blackfly-s camera)
or zero (auto gain). if gain > max, it will be set to max allowed value.
Default is 0, auto gain which is set according to target grey value or autoexposure settings"/>
<arg name="target_grey_value" default="0" doc="AutoExposureTargetGreyValue min: 4 max: 99 if set below 4,
AutoExposureTargetGreyValueAuto will be set to continuous(auto)
also available as dynamic reconfigurable parameter.
This parameter has no meaning when auto exposure and auto gain are off" />
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
<arg name="live" default="false" doc="Show images on screen GUI"/>
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
<arg name="output" default="screen" doc="display output to screen or log file"/>
<arg name="save" default="false" doc="flag whether images should be saved or not"/>
<arg name="save_path" default="~" doc="location to save the image data"/>
<arg name="save_type" default="bmp" doc="Type of file type to save to when saving images locally: binary, tiff, bmp, jpeg etc." />
<arg name="soft_framerate" default="30" doc="When hybrid software triggering is used, this controls the FPS, 0=as fast as possible"/>
<arg name="time" default="false" doc="Show time/FPS on output"/>
<arg name="to_ros" default="true" doc="Flag whether images should be published to ROS" />
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
<arg name="max_rate_save" default="false" doc="Flag for max rate mode which is when the master triggerst the slaves and saves images at maximum rate possible" />
<!-- nodelet manager params-->
<arg name="manager" default="vision_nodelet_manager" doc="name of the nodelet manager, comes handy when launching multiple nodelets from different launch files" />
<arg name="external_manager" default="false" doc="If set to False(default), creates a nodelet manager with $(arg manager).
If True, the acquisition/Capture waits for the nodelet_manager name $(arg manager)" />
<!-- Capture nodelet params-->
<arg name="tf_prefix" default="" doc="will prefix (arg tf_prefix)/ to existing frame_id in Image msg and camerainfo msg" />
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/test_params.yaml" doc="File specifying the parameters of the camera_array"/>
<!-- start the nodelet manager if $(arg start_nodelet_manager) is true-->
<node pkg="nodelet" type="nodelet" name="$(arg manager)" args="manager" output="screen" unless="$(arg external_manager)" />
<!-- load the acquisition nodelet -->
<node pkg="nodelet" type="nodelet" name="acquisition_node"
args="load acquisition/Capture $(arg manager)" >
<!-- load the acquisition node parameters file. Note any parameters provided in this file will
override what is in the yaml file. Thus use it to set parameters camer_array configuration params -->
<rosparam command="load" file="$(arg config_file)" />
<!-- Load parameters onto server using argument or default values above -->
<param name="exposure_time" value="$(arg exposure_time)" />
<param name="external_trigger" value="$(arg external_trigger)" />
<param name="gain" value="$(arg gain)"/>
<param name="target_grey_value" value="$(arg target_grey_value)" />
<param name="binning" value="$(arg binning)" />
<param name="color" value="$(arg color)" />
<param name="frames" value="$(arg frames)" />
<param name="live" value="$(arg live)" />
<param name="live_grid" value="$(arg live_grid)" />
<param name="save" value="$(arg save)" />
<param name="save_type" value="$(arg save_type)" />
<param name="save_path" value="$(arg save_path)" />
<param name="soft_framerate" value="$(arg soft_framerate)" />
<param name="time" value="$(arg time)" />
<param name="utstamps" value="$(arg utstamps)" />
<param name="to_ros" value="$(arg to_ros)"/>
<param name="max_rate_save" value="$(arg max_rate_save)" />
<param name="tf_prefix" value="$(arg tf_prefix)" />
</node>
</launch>