2017-08-12 21:00:18 -03:00
|
|
|
<launch>
|
|
|
|
<!-- Command Line Arguments -->
|
2019-01-19 20:51:49 -04:00
|
|
|
<arg name="sensor_id" default="0" /> <!-- The sensor id of the camera -->
|
|
|
|
<arg name="cam_name" default="csi_cam_$(arg sensor_id)" /> <!-- The name of the camera (corrsponding to the camera info) -->
|
2017-08-23 17:11:30 -03:00
|
|
|
<arg name="frame_id" default="/$(arg cam_name)_link" /> <!-- The TF frame ID. -->
|
|
|
|
<arg name="sync_sink" default="true" /> <!-- Synchronize the app sink. Setting this to false may resolve problems with sub-par framerates. -->
|
|
|
|
<arg name="width" default="1920" /> <!-- Image Width -->
|
|
|
|
<arg name="height" default="1080" /> <!-- Image Height -->
|
|
|
|
<arg name="fps" default="30" /> <!-- Desired framerate. True framerate may not reach this if set too high. -->
|
2017-08-12 21:00:18 -03:00
|
|
|
|
|
|
|
<!-- Make arguments available to parameter server -->
|
2019-01-19 20:51:49 -04:00
|
|
|
<param name="$(arg cam_name)/camera_id" type="int" value="$(arg sensor_id)" />
|
2017-08-12 21:00:18 -03:00
|
|
|
<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)" />
|
|
|
|
|
2017-08-23 17:11:30 -03:00
|
|
|
<!-- Define the GSCAM pipeline -->
|
2019-12-05 12:00:05 -04:00
|
|
|
<env name="GSCAM_CONFIG" value="nvarguscamerasrc sensor-id=$(arg sensor_id) ! video/x-raw(memory:NVMM),
|
2017-08-23 17:11:30 -03:00
|
|
|
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" />
|
|
|
|
|
|
|
|
<!-- Start the GSCAM node -->
|
2017-08-12 21:00:18 -03:00
|
|
|
<node pkg="gscam" type="gscam" name="$(arg cam_name)">
|
|
|
|
<param name="camera_name" value="$(arg cam_name)" />
|
2017-08-23 17:11:30 -03:00
|
|
|
<param name="frame_id" value="$(arg frame_id)" />
|
|
|
|
<param name="sync_sink" value="$(arg sync_sink)" />
|
2017-08-12 21:00:18 -03:00
|
|
|
<remap from="camera/image_raw" to="$(arg cam_name)/image_raw" />
|
2017-08-23 17:11:30 -03:00
|
|
|
<remap from="/set_camera_info" to="$(arg cam_name)/set_camera_info" />
|
2017-08-12 21:00:18 -03:00
|
|
|
</node>
|
|
|
|
</launch>
|