Adding Network streaming
This commit is contained in:
parent
7ddf6735fe
commit
8cc689b2bd
@ -1,6 +1,6 @@
|
||||
image_width: 1280
|
||||
image_height: 720
|
||||
camera_name: narrow_stereo/right
|
||||
camera_name: right
|
||||
camera_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
|
34
tcp_cameras.launch
Normal file
34
tcp_cameras.launch
Normal file
@ -0,0 +1,34 @@
|
||||
<launch>
|
||||
|
||||
<!-- Command Line Arguments -->
|
||||
<arg name="sync_sink" default="true" /> <!-- Synchronize the app sink -->
|
||||
<arg name="width" default="1280" /> <!-- Image Width -->
|
||||
<arg name="height" default="720" /> <!-- Image Height -->
|
||||
<arg name="fps" default="60" /> <!-- Desired framerate -->
|
||||
|
||||
<!-- Make arguments available to parameter server -->
|
||||
<param name="image_width" type="int" value="$(arg width)" />
|
||||
<param name="image_height" type="int" value="$(arg height)" />
|
||||
<param name="target_fps" type="int" value="$(arg fps)" />
|
||||
|
||||
<group ns="stereo">
|
||||
<node name="right" pkg="gscam" type="gscam" output="screen">
|
||||
<param name="camera_name" value="right" />
|
||||
<!--<param name="gscam_config" value="nvcamerasrc sensor-id=0 auto-exposure=1 aeLock=1 ! 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" />-->
|
||||
<param name="gscam_config" value=" udpsrc port=5000 ! application/x-rtp,encoding-name=H264,payload=96 ! rtph264depay ! h264parse ! avdec_h264 ! video/x-raw, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR" />
|
||||
<param name="camera_id" value="0" />
|
||||
<param name="frame_id" value="right_link" />
|
||||
<param name="sync_sink" value="true" />
|
||||
<param name="right/image_width" type="int" value="$(arg width)" />
|
||||
<param name="right/image_height" type="int" value="$(arg height)" />
|
||||
<param name="right/target_fps" type="int" value="$(arg fps)" />
|
||||
<param name="camera_info_url" value="package://jetson_csi_cam/calibration-right.yaml" />
|
||||
<param name="image_encoding_" value="jpeg" />
|
||||
<remap from="camera/image_raw" to="right/image_raw" />
|
||||
<remap from="camera/camera_info" to="right/camera_info" />
|
||||
<remap from="set_camera_info" to="camera_info" />
|
||||
</node>
|
||||
|
||||
</group>
|
||||
|
||||
</launch>
|
Loading…
Reference in New Issue
Block a user