jetson_csi_cam/jetson_csi_cam.launch
2017-08-12 20:00:18 -04:00

23 lines
1.1 KiB
XML

<launch>
<!-- Command Line Arguments -->
<arg name="cam_name" default="csi_cam" />
<arg name="width" default="2840" />
<arg name="height" default="2160" />
<arg name="fps" default="30" />
<!-- Make arguments available to parameter server -->
<param name="$(arg cam_name)/image_width" type="int" value="$(arg width)" />
<param name="$(arg cam_name)/image_height" type="int" value="$(arg height)" />
<param name="$(arg cam_name)/target_fps" type="int" value="$(arg fps)" />
<!-- Start the GSCAM node -->
<env name="GSCAM_CONFIG" value="nvcamerasrc ! video/x-raw(memory:NVMM),
width=(int)$(arg width), height=(int)$(arg height), format=(string)I420, framerate=(fraction)$(arg fps)/1 ! nvvidconv flip-method=2 !
video/x-raw, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR" />
<node pkg="gscam" type="gscam" name="$(arg cam_name)">
<param name="camera_name" value="$(arg cam_name)" />
<param name="camera_info_url" value="package://localcam/calibrations/${NAME}.yaml" />
<remap from="camera/image_raw" to="$(arg cam_name)/image_raw" />
</node>
</launch>