Skip to content

Commit 8d5033c

Browse files
committed
adding external trigger launch file
1 parent c6e0c23 commit 8d5033c

File tree

1 file changed

+65
-0
lines changed

1 file changed

+65
-0
lines changed
Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
<launch>
2+
<!-- configure console output verbosity mode:debug_console.conf or std_console.conf -->
3+
<env name="ROSCONSOLE_CONFIG_FILE" value="$(find spinnaker_sdk_camera_driver)/cfg/std_console.conf"/>
4+
5+
<!-- acquisition spinnaker params-->
6+
<arg name="binning" default="1" doc="Binning for cameras, when changing from 2 to 1 cameras need to be unplugged and replugged"/>
7+
<arg name="color" default="false" doc="Should color images be used (only works on models that support color images)"/>
8+
<arg name="exposure_time" default="0" doc="Exposure_time setting for cameras"/>
9+
<arg name="external_trigger" default="true" doc="External trigger (No camera is master)"/>
10+
<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" />
11+
<arg name="frames" default="3400" doc="Numer of frames to save/view 0=ON"/>
12+
<arg name="live" default="false" doc="Show images on screen GUI"/>
13+
<arg name="live_grid" default="false" doc="Show images on screen GUI in a grid"/>
14+
<arg name="output" default="screen" doc="display output to screen or log file"/>
15+
<arg name="save" default="false" doc="flag whether images should be saved or not"/>
16+
<arg name="save_path" default="/media/jagatpreet/Data/datasets/vio_rosbags/vio_rig/dummy" doc="location to save the image data"/>
17+
<arg name="save_type" default="bmp" doc="Type of file type to save to when saving images locally: binary, tiff, bmp, jpeg etc." />
18+
<arg name="soft_framerate" default="30" doc="When hybrid software triggering is used, this controls the FPS, 0=as fast as possible"/>
19+
<arg name="time" default="false" doc="Show time/FPS on output"/>
20+
<arg name="to_ros" default="true" doc="Flag whether images should be published to ROS" />
21+
<arg name="utstamps" default="false" doc="Flag whether each image should have Unique timestamps vs the master cams time stamp for all" />
22+
<arg name="max_rate_save" default="true" doc="Flag for max rate mode which is when the master triggerst the slaves and saves images at maximum rate possible" />
23+
24+
25+
<!-- nodelet manager params-->
26+
<arg name="manager" default="vision_nodelet_manager" doc="name of the nodelet manager, comes handy when launching multiple nodelets from different launch files" />
27+
<arg name="external_manager" default="false" doc="If set to False(default), creates a nodelet manager with $(arg manager).
28+
If True, the acquisition/Capture waits for the nodelet_manager name $(arg manager)" />
29+
30+
<!-- Capture nodelet params-->
31+
<arg name="tf_prefix" default="" doc="will prefix (arg tf_prefix)/ to existing frame_id in Image msg and camerainfo msg" />
32+
<arg name="config_file" default="$(find spinnaker_sdk_camera_driver)/params/external_trigger_params.yaml" doc="File specifying the parameters of the camera_array"/>
33+
34+
<!-- start the nodelet manager if $(arg start_nodelet_manager) is true-->
35+
<node pkg="nodelet" type="nodelet" name="$(arg manager)" args="manager" output="screen" unless="$(arg external_manager)" />
36+
37+
<!-- load the acquisition nodelet -->
38+
<node pkg="nodelet" type="nodelet" name="acquisition_node"
39+
args="load acquisition/Capture $(arg manager)" >
40+
<!-- load the acquisition node parameters file. Note any parameters provided in this file will
41+
override what is in the yaml file. Thus use it to set parameters camer_array configuration params -->
42+
<rosparam command="load" file="$(arg config_file)" />
43+
44+
<!-- Load parameters onto server using argument or default values above -->
45+
<param name="exposure_time" value="$(arg exposure_time)" />
46+
<param name="external_trigger" value="$(arg external_trigger)" />
47+
<param name="target_grey_value" value="$(arg target_grey_value)" />
48+
<param name="binning" value="$(arg binning)" />
49+
<param name="color" value="$(arg color)" />
50+
<param name="frames" value="$(arg frames)" />
51+
<param name="live" value="$(arg live)" />
52+
<param name="live_grid" value="$(arg live_grid)" />
53+
<param name="save" value="$(arg save)" />
54+
<param name="save_type" value="$(arg save_type)" />
55+
<param name="save_path" value="$(arg save_path)" />
56+
<param name="soft_framerate" value="$(arg soft_framerate)" />
57+
<param name="time" value="$(arg time)" />
58+
<param name="utstamps" value="$(arg utstamps)" />
59+
<param name="to_ros" value="$(arg to_ros)"/>
60+
<param name="max_rate_save" value="$(arg max_rate_save)" />
61+
<param name="tf_prefix" value="$(arg tf_prefix)" />
62+
63+
</node>
64+
65+
</launch>

0 commit comments

Comments
 (0)