Compare commits
10 Commits
master
...
gscam_node
Author | SHA1 | Date | |
---|---|---|---|
|
296ef2baa1 | ||
|
40bff0db8d | ||
|
2d3309ebcb | ||
|
d7442d098d | ||
|
00149d2bdc | ||
|
7b7a264e45 | ||
|
d532d5fe2e | ||
|
68fe5bf0e5 | ||
|
05fd93138d | ||
|
fd030b3e47 |
0
.goutputstream-B0TIZ0
Normal file
0
.goutputstream-B0TIZ0
Normal file
1773
camera_overrides.isp
Normal file
1773
camera_overrides.isp
Normal file
File diff suppressed because it is too large
Load Diff
@ -4,23 +4,24 @@ camera_name: left
|
||||
camera_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [ 873.68467, 0. , 657.89992,
|
||||
0. , 871.77207, 360.60431,
|
||||
0. , 0. , 1. ]
|
||||
data: [907.91127, 0. , 604.06352,
|
||||
0. , 906.83626, 390.59699,
|
||||
0. , 0. , 1. ]
|
||||
camera_model: plumb_bob
|
||||
distortion_coefficients:
|
||||
rows: 1
|
||||
cols: 5
|
||||
data: [-0.345111, 0.109548, 0.007497, 0.001845, 0.000000]
|
||||
data: [-0.391252, 0.163859, -0.005408, 0.004813, 0.000000]
|
||||
rectification_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [ 0.999594 , 0.01840935, 0.02174699,
|
||||
-0.0188595 , 0.99960827, 0.02067903,
|
||||
-0.02135778, -0.02108077, 0.99954962]
|
||||
data: [ 0.99300094, -0.00822023, -0.11782007,
|
||||
0.00780606, 0.99996163, -0.00397631,
|
||||
0.11784823, 0.00302877, 0.993027 ]
|
||||
projection_matrix:
|
||||
rows: 3
|
||||
cols: 4
|
||||
data: [ 869.23405, 0. , 590.64311, 0. ,
|
||||
0. , 869.23405, 366.70978, 0. ,
|
||||
0. , 0. , 1. , 0. ]
|
||||
data: [896.45054, 0. , 764.25062, 0. ,
|
||||
0. , 896.45054, 388.10495, 0. ,
|
||||
0. , 0. , 1. , 0. ]
|
||||
|
||||
|
@ -4,17 +4,17 @@ camera_name: left
|
||||
camera_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [216.587179, 0.000000, 152.272854, 0.000000, 288.814935, 123.514917, 0.000000, 0.000000, 1.000000]
|
||||
data: [225.826003, 0.000000, 170.235423, 0.000000, 302.560777, 116.353107, 0.000000, 0.000000, 1.000000]
|
||||
distortion_model: plumb_bob
|
||||
distortion_coefficients:
|
||||
rows: 1
|
||||
cols: 5
|
||||
data: [-0.400277, 0.190072, -0.003888, 0.002995, 0.000000]
|
||||
data: [-0.380508, 0.124231, -0.001392, -0.009495, 0.000000]
|
||||
rectification_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [0.990367, 0.059907, -0.124836, -0.059914, 0.998197, 0.003704, 0.124833, 0.003811, 0.992170]
|
||||
data: [0.994997, 0.008482, 0.099545, -0.009047, 0.999945, 0.005227, -0.099495, -0.006101, 0.995019]
|
||||
projection_matrix:
|
||||
rows: 3
|
||||
cols: 4
|
||||
data: [296.195350, 0.000000, 215.261782, 0.000000, 0.000000, 296.195350, 120.768448, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
|
||||
data: [294.081451, 0.000000, 126.699184, 0.000000, 0.000000, 294.081451, 115.697273, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
|
||||
|
27
left_800x600.yaml
Normal file
27
left_800x600.yaml
Normal file
@ -0,0 +1,27 @@
|
||||
image_width: 800
|
||||
image_height: 600
|
||||
camera_name: left
|
||||
camera_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [546.82833, 0. , 395.41899,
|
||||
0. , 728.53633, 307.08189,
|
||||
0. , 0. , 1. ]
|
||||
camera_model: plumb_bob
|
||||
distortion_coefficients:
|
||||
rows: 1
|
||||
cols: 5
|
||||
data: [-0.394573, 0.162349, -0.002198, -0.001344, 0.000000]
|
||||
rectification_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [ 0.99984948, 0.00197076, -0.0172378 ,
|
||||
-0.00184396, 0.99997115, 0.00736835,
|
||||
0.01725183, -0.00733546, 0.99982427]
|
||||
projection_matrix:
|
||||
rows: 3
|
||||
cols: 4
|
||||
data: [704.41879, 0. , 419.01768, 0. ,
|
||||
0. , 704.41879, 306.11043, 0. ,
|
||||
0. , 0. , 1. , 0. ]
|
||||
|
@ -4,23 +4,24 @@ camera_name: right
|
||||
camera_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [ 879.81628, 0. , 631.55074,
|
||||
0. , 877.90835, 349.78586,
|
||||
0. , 0. , 1. ]
|
||||
data: [935.14307, 0. , 620.65919,
|
||||
0. , 932.02901, 398.37732,
|
||||
0. , 0. , 1. ]
|
||||
camera_model: plumb_bob
|
||||
distortion_coefficients:
|
||||
rows: 1
|
||||
cols: 5
|
||||
data: [-0.359859, 0.129457, 0.002187, 0.006292, 0.000000]
|
||||
data: [-0.397349, 0.154127, -0.004348, 0.004203, 0.000000]
|
||||
rectification_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [ 0.99680464, 0.0451326 , 0.06590573,
|
||||
-0.04374539, 0.99879285, -0.02234257,
|
||||
-0.06683455, 0.0193881 , 0.99757568]
|
||||
data: [ 0.99413297, -0.00792457, -0.10787415,
|
||||
0.00830358, 0.99996083, 0.00306465,
|
||||
0.10784563, -0.00394241, 0.99415983]
|
||||
projection_matrix:
|
||||
rows: 3
|
||||
cols: 4
|
||||
data: [ 869.23405, 0. , 590.64311, -46.17111,
|
||||
0. , 869.23405, 366.70978, 0. ,
|
||||
0. , 0. , 1. , 0. ]
|
||||
data: [896.45054, 0. , 764.25062, -48.59953,
|
||||
0. , 896.45054, 388.10495, 0. ,
|
||||
0. , 0. , 1. , 0. ]
|
||||
|
||||
|
@ -4,17 +4,17 @@ camera_name: right
|
||||
camera_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [223.401364, 0.000000, 161.232191, 0.000000, 297.556234, 124.851974, 0.000000, 0.000000, 1.000000]
|
||||
data: [229.029286, 0.000000, 170.917223, 0.000000, 306.208067, 116.795495, 0.000000, 0.000000, 1.000000]
|
||||
distortion_model: plumb_bob
|
||||
distortion_coefficients:
|
||||
rows: 1
|
||||
cols: 5
|
||||
data: [-0.390714, 0.159344, -0.002090, -0.002267, 0.000000]
|
||||
data: [-0.378035, 0.121756, 0.001324, -0.008491, 0.000000]
|
||||
rectification_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [0.988569, 0.058607, -0.138916, -0.058599, 0.998273, 0.004148, 0.138919, 0.004040, 0.990296]
|
||||
data: [0.997868, 0.000357, 0.065259, 0.000013, 0.999984, -0.005673, -0.065260, 0.005662, 0.997852]
|
||||
projection_matrix:
|
||||
rows: 3
|
||||
cols: 4
|
||||
data: [296.195350, 0.000000, 215.261782, -18.019714, 0.000000, 296.195350, 120.768448, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
|
||||
data: [294.081451, 0.000000, 126.699184, -17.052882, 0.000000, 294.081451, 115.697273, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
|
||||
|
27
right_800x600.yaml
Normal file
27
right_800x600.yaml
Normal file
@ -0,0 +1,27 @@
|
||||
image_width: 800
|
||||
image_height: 600
|
||||
camera_name: right
|
||||
camera_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [556.66939, 0. , 402.50992,
|
||||
0. , 741.65684, 304.22578,
|
||||
0. , 0. , 1. ]
|
||||
camera_model: plumb_bob
|
||||
distortion_coefficients:
|
||||
rows: 1
|
||||
cols: 5
|
||||
data: [-0.394982, 0.162894, 0.002350, -0.001648, 0.000000]
|
||||
rectification_matrix:
|
||||
rows: 3
|
||||
cols: 3
|
||||
data: [ 0.99967835, -0.00220518, -0.02526515,
|
||||
0.00201935, 0.99997074, -0.00737829,
|
||||
0.02528068, 0.00732489, 0.99965356]
|
||||
projection_matrix:
|
||||
rows: 3
|
||||
cols: 4
|
||||
data: [704.41879, 0. , 419.01768, -36.86134,
|
||||
0. , 704.41879, 306.11043, 0. ,
|
||||
0. , 0. , 1. , 0. ]
|
||||
|
76
video-daylight-nodelet-1280x720.launch
Normal file
76
video-daylight-nodelet-1280x720.launch
Normal file
@ -0,0 +1,76 @@
|
||||
<launch>
|
||||
<!-- <arg name="DEVICE" default="/dev/video0"/> -->
|
||||
<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="20" /> <!-- 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 pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager" output="screen"/>
|
||||
|
||||
<node pkg="nodelet" type="nodelet" name="GSCamNodeletLeft" args="load gscam/GSCamNodelet standalone_nodelet respawn:=true" output="screen">
|
||||
<param name="camera_name" value="left"/>
|
||||
<param name="camera_info_url" value="package://jetson_csi_cam/left_1280x720.yaml"/>
|
||||
<param name="gscam_config" value="nvarguscamerasrc sensor-id=1 aelock=true awblock=true ! video/x-raw(memory:NVMM), width=(int)$(arg width), height=(int)$(arg height), format=(string)NV12,framerate=(fraction)$(arg fps)/1 ! nvvidconv flip-method=2 ! video/x-raw, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR" />
|
||||
<param name="frame_id" value="left_link"/>
|
||||
<param name="sync_sink" value="true"/>
|
||||
<param name="left/image_width" type="int" value="$(arg width)" />
|
||||
<param name="left/image_height" type="int" value="$(arg height)" />
|
||||
<param name="left/target_fps" type="int" value="$(arg fps)" />
|
||||
<remap from="camera/image_raw" to="left/image_raw" />
|
||||
<remap from="camera/camera_info" to="left/camera_info" />
|
||||
<!--<remap from="/set_camera_info" to="left/set_camera_info" />-->
|
||||
</node>
|
||||
|
||||
<node pkg="nodelet" type="nodelet" name="GSCamNodeletRight" args="standalone gscam/GSCamNodelet" output="screen">
|
||||
<param name="camera_name" value="right"/>
|
||||
<param name="camera_info_url" value="package://jetson_csi_cam/right_1280x720.yaml"/>
|
||||
<param name="gscam_config" value="nvarguscamerasrc sensor-id=0 aelock=true awblock=true ! video/x-raw(memory:NVMM), width=(int)$(arg width), height=(int)$(arg height), format=(string)NV12,framerate=(fraction)$(arg fps)/1 ! nvvidconv flip-method=2 ! video/x-raw, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR" />
|
||||
<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)" />
|
||||
<remap from="camera/image_raw" to="right/image_raw" />
|
||||
<remap from="camera/camera_info" to="right/camera_info" />
|
||||
<!--<remap from="/set_camera_info" to="right/set_camera_info" />-->
|
||||
</node>
|
||||
|
||||
<!--<node pkg="nodelet" type="nodelet" name="ImageViewNodeletLeft"
|
||||
args="load image_view/image image:=/stereo/right/image_raw standalone_nodelet"
|
||||
respawn="false" output="screen" >
|
||||
</node>
|
||||
<node pkg="nodelet" type="nodelet" name="ImageViewNodeletRight"
|
||||
args="standalone image_view/image image:=/stereo/left/image_raw"
|
||||
respawn="false" output="screen" >
|
||||
</node>
|
||||
|
||||
<include file="$(find image_proc)/launch/image_proc.launch"
|
||||
ns="left">
|
||||
<arg name="manager" value="standalone_nodelet" />
|
||||
<arg name="respawn" value="false" />
|
||||
</include>
|
||||
|
||||
<! Basic processing for right camera
|
||||
<include file="$(find image_proc)/launch/image_proc.launch"
|
||||
ns="right">
|
||||
<arg name="manager" value="standalone_nodelet" />
|
||||
<arg name="respawn" value="false" />
|
||||
</include>
|
||||
|
||||
<node pkg="nodelet" type="nodelet" name="disparity"
|
||||
args="load gpu_stereo_image_proc/libsgm_disparity standalone_nodelet"
|
||||
respawn="false" output="screen">
|
||||
<param name="approximate_sync" value="true" />
|
||||
</node>-->
|
||||
|
||||
</group>
|
||||
|
||||
</launch>
|
96
video-daylight-nodelet-800x600.launch
Normal file
96
video-daylight-nodelet-800x600.launch
Normal file
@ -0,0 +1,96 @@
|
||||
<launch>
|
||||
<!-- <arg name="DEVICE" default="/dev/video0"/> -->
|
||||
<arg name="sync_sink" default="true" /> <!-- Synchronize the app sink -->
|
||||
<arg name="width" default="800" /> <!-- Image Width -->
|
||||
<arg name="height" default="600" /> <!-- Image Height -->
|
||||
<arg name="fps" default="20" />
|
||||
<arg name="respawn" default="false" />
|
||||
<arg name="left" default="left" />
|
||||
<arg name="right" default="right" />
|
||||
<arg name="approximate_sync" default="true" /> <!-- Desired framerate -->
|
||||
<arg if="$(arg respawn)" name="bond" value="" />
|
||||
<arg unless="$(arg respawn)" name="bond" value="--no-bond" />
|
||||
|
||||
<!-- 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 pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager" output="screen"/>
|
||||
|
||||
<node pkg="nodelet" type="nodelet" name="GSCamNodeletLeft" args="load gscam/GSCamNodelet standalone_nodelet respawn:=true" output="screen">
|
||||
<param name="camera_name" value="left"/>
|
||||
<param name="camera_info_url" value="package://jetson_csi_cam/left_800x600.yaml"/>
|
||||
<param name="gscam_config" value="nvarguscamerasrc sensor-id=1 aelock=true awblock=true ! video/x-raw(memory:NVMM), width=(int)$(arg width), height=(int)$(arg height), format=(string)NV12,framerate=(fraction)$(arg fps)/1 ! nvvidconv flip-method=2 ! video/x-raw, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR" />
|
||||
<param name="frame_id" value="left_link"/>
|
||||
<param name="sync_sink" value="true"/>
|
||||
<param name="left/image_width" type="int" value="$(arg width)" />
|
||||
<param name="left/image_height" type="int" value="$(arg height)" />
|
||||
<param name="left/target_fps" type="int" value="$(arg fps)" />
|
||||
<remap from="camera/image_raw" to="left/image_raw" />
|
||||
<remap from="camera/camera_info" to="left/camera_info" />
|
||||
<!--<remap from="/set_camera_info" to="left/set_camera_info" />-->
|
||||
</node>
|
||||
<node pkg="tf" type="static_transform_publisher" name="fcu_to_Left_link" args="0.08505 0.0265 -0.0562 -0.5958106 0.5966497 -0.3801439 0.3801439 fcu left_link 10" />
|
||||
|
||||
<node pkg="nodelet" type="nodelet" name="GSCamNodeletRight" args="standalone gscam/GSCamNodelet" output="screen">
|
||||
<param name="camera_name" value="right"/>
|
||||
<param name="camera_info_url" value="package://jetson_csi_cam/right_800x600.yaml"/>
|
||||
<param name="gscam_config" value="nvarguscamerasrc sensor-id=0 aelock=true awblock=true ! video/x-raw(memory:NVMM), width=(int)$(arg width), height=(int)$(arg height), format=(string)NV12,framerate=(fraction)$(arg fps)/1 ! nvvidconv flip-method=2 ! video/x-raw, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR" />
|
||||
<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)" />
|
||||
<remap from="camera/image_raw" to="right/image_raw" />
|
||||
<remap from="camera/camera_info" to="right/camera_info" />
|
||||
<!--<remap from="/set_camera_info" to="right/set_camera_info" />-->
|
||||
</node>
|
||||
<node pkg="tf" type="static_transform_publisher" name="fcu_to_Right_link" args="0.08505 -0.0265 -0.0562 -0.5958106 0.5966497 -0.3801439 0.3801439 fcu right_link 10"/>
|
||||
|
||||
<!--<node pkg="nodelet" type="nodelet" name="ImageViewNodeletLeft"
|
||||
args="load image_view/image image:=/stereo/right/image_raw standalone_nodelet"
|
||||
respawn="false" output="screen" >
|
||||
</node>
|
||||
<node pkg="nodelet" type="nodelet" name="ImageViewNodeletRight"
|
||||
args="standalone image_view/image image:=/stereo/left/image_raw"
|
||||
respawn="false" output="screen" >
|
||||
</node>
|
||||
|
||||
<include file="$(find image_proc)/launch/image_proc.launch"
|
||||
ns="left">
|
||||
<arg name="manager" value="standalone_nodelet" />
|
||||
<arg name="respawn" value="false" />
|
||||
</include>
|
||||
|
||||
<! Basic processing for right camera
|
||||
<include file="$(find image_proc)/launch/image_proc.launch"
|
||||
ns="right">
|
||||
<arg name="manager" value="standalone_nodelet" />
|
||||
<arg name="respawn" value="false" />
|
||||
</include>
|
||||
|
||||
<node pkg="nodelet" type="nodelet" name="disparity"
|
||||
args="load gpu_stereo_image_proc/libsgm_disparity standalone_nodelet"
|
||||
respawn="false" output="screen">
|
||||
<param name="approximate_sync" value="true" />
|
||||
</node>-->
|
||||
<node pkg="nodelet" type="nodelet" name="Image2RTSPNodelet" args="load image2rtsp/Image2RTSPNodelet standalone_nodelet --no-bond" output="screen">
|
||||
<!-- Read the stream setup file -->
|
||||
<rosparam command="load" file="$(find ros_rtsp)/config/stream_setup.yaml" />
|
||||
</node>
|
||||
<!--<include file="$(find gpu_stereo_image_proc)/launch/libsgm_stereo_image_proc.launch">
|
||||
<arg name="manager" value="/stereo/standalone_nodelet"/>
|
||||
</include>-->
|
||||
|
||||
|
||||
</group>
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
</launch>
|
96
video-daylight-nodelet.launch
Normal file
96
video-daylight-nodelet.launch
Normal file
@ -0,0 +1,96 @@
|
||||
<launch>
|
||||
<!-- <arg name="DEVICE" default="/dev/video0"/> -->
|
||||
<arg name="sync_sink" default="true" /> <!-- Synchronize the app sink -->
|
||||
<arg name="width" default="320" /> <!-- Image Width -->
|
||||
<arg name="height" default="240" /> <!-- Image Height -->
|
||||
<arg name="fps" default="20" />
|
||||
<arg name="respawn" default="false" />
|
||||
<arg name="left" default="left" />
|
||||
<arg name="right" default="right" />
|
||||
<arg name="approximate_sync" default="true" /> <!-- Desired framerate -->
|
||||
<arg if="$(arg respawn)" name="bond" value="" />
|
||||
<arg unless="$(arg respawn)" name="bond" value="--no-bond" />
|
||||
|
||||
<!-- 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 pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager" output="screen"/>
|
||||
|
||||
<node pkg="nodelet" type="nodelet" name="GSCamNodeletLeft" args="load gscam/GSCamNodelet standalone_nodelet respawn:=true" output="screen">
|
||||
<param name="camera_name" value="left"/>
|
||||
<param name="camera_info_url" value="package://jetson_csi_cam/left_320x240.yaml"/>
|
||||
<param name="gscam_config" value="nvarguscamerasrc sensor-id=1 aelock=true awblock=true ! video/x-raw(memory:NVMM), width=(int)$(arg width), height=(int)$(arg height), format=(string)NV12,framerate=(fraction)$(arg fps)/1 ! nvvidconv flip-method=2 ! video/x-raw, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR" />
|
||||
<param name="frame_id" value="left_link"/>
|
||||
<param name="sync_sink" value="true"/>
|
||||
<param name="left/image_width" type="int" value="$(arg width)" />
|
||||
<param name="left/image_height" type="int" value="$(arg height)" />
|
||||
<param name="left/target_fps" type="int" value="$(arg fps)" />
|
||||
<remap from="camera/image_raw" to="left/image_raw" />
|
||||
<remap from="camera/camera_info" to="left/camera_info" />
|
||||
<!--<remap from="/set_camera_info" to="left/set_camera_info" />-->
|
||||
</node>
|
||||
<node pkg="tf" type="static_transform_publisher" name="fcu_to_Left_link" args="0.08505 0.0265 -0.0562 -0.5958106 0.5966497 -0.3801439 0.3801439 fcu left_link 10" />
|
||||
|
||||
<node pkg="nodelet" type="nodelet" name="GSCamNodeletRight" args="standalone gscam/GSCamNodelet" output="screen">
|
||||
<param name="camera_name" value="right"/>
|
||||
<param name="camera_info_url" value="package://jetson_csi_cam/right_320x240.yaml"/>
|
||||
<param name="gscam_config" value="nvarguscamerasrc sensor-id=0 aelock=true awblock=true ! video/x-raw(memory:NVMM), width=(int)$(arg width), height=(int)$(arg height), format=(string)NV12,framerate=(fraction)$(arg fps)/1 ! nvvidconv flip-method=2 ! video/x-raw, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR" />
|
||||
<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)" />
|
||||
<remap from="camera/image_raw" to="right/image_raw" />
|
||||
<remap from="camera/camera_info" to="right/camera_info" />
|
||||
<!--<remap from="/set_camera_info" to="right/set_camera_info" />-->
|
||||
</node>
|
||||
<node pkg="tf" type="static_transform_publisher" name="fcu_to_Right_link" args="0.08505 -0.0265 -0.0562 -0.5958106 0.5966497 -0.3801439 0.3801439 fcu right_link 10"/>
|
||||
|
||||
<!--<node pkg="nodelet" type="nodelet" name="ImageViewNodeletLeft"
|
||||
args="load image_view/image image:=/stereo/right/image_raw standalone_nodelet"
|
||||
respawn="false" output="screen" >
|
||||
</node>
|
||||
<node pkg="nodelet" type="nodelet" name="ImageViewNodeletRight"
|
||||
args="standalone image_view/image image:=/stereo/left/image_raw"
|
||||
respawn="false" output="screen" >
|
||||
</node>
|
||||
|
||||
<include file="$(find image_proc)/launch/image_proc.launch"
|
||||
ns="left">
|
||||
<arg name="manager" value="standalone_nodelet" />
|
||||
<arg name="respawn" value="false" />
|
||||
</include>
|
||||
|
||||
<! Basic processing for right camera
|
||||
<include file="$(find image_proc)/launch/image_proc.launch"
|
||||
ns="right">
|
||||
<arg name="manager" value="standalone_nodelet" />
|
||||
<arg name="respawn" value="false" />
|
||||
</include>
|
||||
|
||||
<node pkg="nodelet" type="nodelet" name="disparity"
|
||||
args="load gpu_stereo_image_proc/libsgm_disparity standalone_nodelet"
|
||||
respawn="false" output="screen">
|
||||
<param name="approximate_sync" value="true" />
|
||||
</node>-->
|
||||
<node pkg="nodelet" type="nodelet" name="Image2RTSPNodelet" args="load image2rtsp/Image2RTSPNodelet standalone_nodelet --no-bond" output="screen">
|
||||
<!-- Read the stream setup file -->
|
||||
<rosparam command="load" file="$(find ros_rtsp)/config/stream_setup.yaml" />
|
||||
</node>
|
||||
<!--<include file="$(find gpu_stereo_image_proc)/launch/libsgm_stereo_image_proc.launch">
|
||||
<arg name="manager" value="/stereo/standalone_nodelet"/>
|
||||
</include>-->
|
||||
|
||||
|
||||
</group>
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
</launch>
|
Loading…
Reference in New Issue
Block a user