Skip to content

Instantly share code, notes, and snippets.

@garaemon
Last active August 29, 2015 14:06
Show Gist options
  • Select an option

  • Save garaemon/6b9ce695fa3ff5a0a09b to your computer and use it in GitHub Desktop.

Select an option

Save garaemon/6b9ce695fa3ff5a0a09b to your computer and use it in GitHub Desktop.
pgstereo
image_width: 1280
image_height: 960
camera_name: 14137639
camera_matrix:
rows: 3
cols: 3
data: [1214.40086106745, 0, 608.015171891804, 0, 1210.28487583331, 473.81047351168, 0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.305982846402342, 0.118177078455821, -0.00011382700430081, 0.000172165136507537, 0]
rectification_matrix:
rows: 3
cols: 3
data: [0.999926436492223, -0.00375394565993053, -0.0115338413352267, 0.00372371252882844, 0.999989577870599, -0.00264161223175394, 0.0115436375968125, 0.00259846919600649, 0.999929993743997]
projection_matrix:
rows: 3
cols: 4
data: [1168.76146806506, 0, 637.481414794922, -108.648148777126, 0, 1168.76146806506, 470.333045959473, 0, 0, 0, 1, 0]
image_width: 1280
image_height: 960
camera_name: 14137651
camera_matrix:
rows: 3
cols: 3
data: [1217.81154260755, 0, 626.07966825342, 0, 1213.25156796285, 468.538258641717, 0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.309919937550201, 0.132729580432602, 0.000167929789540437, -3.4544193089263e-05, 0]
rectification_matrix:
rows: 3
cols: 3
data: [0.99974120605241, -0.00426152129180926, -0.0223463723487991, 0.00432005993307871, 0.999987360912034, 0.00257198335152166, 0.0223351293492186, -0.00266785540563069, 0.99974698026275]
projection_matrix:
rows: 3
cols: 4
data: [1168.76146806506, 0, 637.481414794922, 0, 0, 1168.76146806506, 470.333045959473, 0, 0, 0, 1, 0]
<launch>
<node pkg="nodelet" type="nodelet" name="manager" args="manager"
output="screen" />
<group ns="left">
<node pkg="nodelet" type="nodelet"
args="load pointgrey_camera_driver/PointGreyCameraNodelet /manager"
name="driver" respawn="true">
<param name="serial" value="14137651" />
</node>
<node pkg="image_view" type="image_view" name="image_view">
<remap from="image" to="image_raw" />
</node>
<node pkg="image_view" type="image_view" name="image_view_rect">
<remap from="image" to="image_rect" />
</node>
</group>
<group ns="right">
<node pkg="nodelet" type="nodelet"
args="load pointgrey_camera_driver/PointGreyCameraNodelet /manager"
name="driver" respawn="true">
<param name="serial" value="14137639" />
</node>
<node pkg="image_view" type="image_view" name="image_view">
<remap from="image" to="image_raw" />
</node>
<node pkg="image_view" type="image_view" name="image_view_rect">
<remap from="image" to="image_rect" />
</node>
</group>
<include file="$(find stereo_image_proc)/launch/stereo_image_proc.launch">
<arg name="manager" type="/manager"/>
<arg name="left" type="half/left_1_2" />
<arg name="right" type="half/right_1_2" />
</include>
<node pkg="nodelet" type="nodelet"
args="load stereo_image_proc/stereo_image_proc /manager"
name="stereo_image_proc" output="screen">
<param name="approximate_sync" value="true" />
<remap from="point2" to="~points2" />
<remap from="disparity" to="~disparity" />
</node>
<node pkg="image_view" type="disparity_view" name="disparity_view">
<remap from="image" to="stereo_image_proc/disparity" />
</node>
<node pkg="rqt_reconfigure" type="rqt_reconfigure" name="rqt_reconfigure" respawn="true"/>
<group ns="half">
<group ns="left_1_2">
<node pkg="nodelet" type="nodelet" args="load resized_image_transport/ImageResizer /manager"
name="image_resizer">
<param name="resize_scale_x" value="0.5" />
<param name="resize_scale_y" value="0.5" />
<remap from="~input/image" to="/left/image_raw" />
<remap from="~output/image" to="image_raw" />
</node>
</group>
<group ns="right_1_2">
<node pkg="nodelet" type="nodelet" args="load resized_image_transport/ImageResizer /manager" name="image_resizer">
<param name="resize_scale_x" value="0.5" />
<param name="resize_scale_y" value="0.5" />
<remap from="~input/image" to="/right/image_raw" />
<remap from="~output/image" to="image_raw" />
</node>
</group>
<node pkg="nodelet" type="nodelet"
args="load stereo_image_proc/stereo_image_proc /manager"
name="stereo_image_proc_2" output="screen">
<param name="approximate_sync" value="true" />
<remap from="left/image_raw" to="left_1_2/image_raw"/>
<remap from="left/camera_info" to="left_1_2/camera_info"/>
<remap from="right/image_raw" to="right_1_2/image_raw"/>
<remap from="right/camera_info" to="right_1_2/camera_info"/>
<remap from="point2" to="~points2" />
<remap from="disparity" to="~disparity" />
</node>
<node pkg="image_view" type="disparity_view" name="disparity_view2">
<remap from="image" to="stereo_image_proc_2/disparity" />
</node>
</group>
<group ns="quater">
<group ns="left_1_4">
<node pkg="nodelet" type="nodelet" args="load resized_image_transport/ImageResizer /manager"
name="image_resizer">
<param name="resize_scale_x" value="0.25" />
<param name="resize_scale_y" value="0.25" />
<remap from="~input/image" to="/left/image_raw" />
<remap from="~output/image" to="image_raw" />
</node>
</group>
<group ns="right_1_4">
<node pkg="nodelet" type="nodelet" args="load resized_image_transport/ImageResizer /manager"
name="image_resizer">
<param name="resize_scale_x" value="0.25" />
<param name="resize_scale_y" value="0.25" />
<remap from="~input/image" to="/right/image_raw" />
<remap from="~output/image" to="image_raw" />
</node>
</group>
<node pkg="nodelet" type="nodelet"
args="load stereo_image_proc/stereo_image_proc /manager"
name="stereo_image_proc_4" output="screen">
<param name="approximate_sync" value="true" />
<remap from="left/image_raw" to="left_1_4/image_raw"/>
<remap from="right/image_raw" to="right_1_4/image_raw"/>
<remap from="left/camera_info" to="left_1_4/camera_info"/>
<remap from="right/camera_info" to="right_1_4/camera_info"/>
<remap from="point2" to="~points2" />
<remap from="disparity" to="~disparity" />
</node>
<node pkg="image_view" type="disparity_view" name="disparity_view4">
<remap from="image" to="stereo_image_proc_4/disparity" />
</node>
</group>
<!-- <node pkg="nodelet" type="nodelet" name="manager" args="manager" output="screen" /> -->
<!-- <node pkg="nodelet" type="nodelet" name="disparity" args="load stereo_image_proc/disparity" /> -->
</launch>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment