new calibration files

This commit is contained in:
AhmedElsafy 2020-02-21 12:06:25 -04:00
parent 40663b2f5d
commit 7c2ff4f649
7 changed files with 89 additions and 15 deletions

Binary file not shown.

26
left_1280x720.yaml Normal file
View File

@ -0,0 +1,26 @@
image_width: 1280
image_height: 720
camera_name: left
camera_matrix:
rows: 3
cols: 3
data: [ 873.68467, 0. , 657.89992,
0. , 871.77207, 360.60431,
0. , 0. , 1. ]
camera_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.345111, 0.109548, 0.007497, 0.001845, 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]
projection_matrix:
rows: 3
cols: 4
data: [ 869.23405, 0. , 590.64311, 0. ,
0. , 869.23405, 366.70978, 0. ,
0. , 0. , 1. , 0. ]

View File

@ -4,17 +4,23 @@ camera_name: left
camera_matrix:
rows: 3
cols: 3
data: [244.429325, 0.000000, 165.897763, 0.000000, 325.915464, 123.820184, 0.000000, 0.000000, 1.000000]
distortion_model: plumb_bob
data: [ 225.48436, 0. , 164.71275,
0. , 299.70005, 118.01326,
0. , 0. , 1. ]
camera_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.412729, 0.153568, -0.000334, -0.003140, 0.000000]
data: [-0.404573, 0.163958, 0.001334, -0.005042, 0.000000]
rectification_matrix:
rows: 3
cols: 3
data: [0.920705, 0.002779, 0.390251, -0.008226, 0.999891, 0.012287, -0.390174, -0.014523, 0.920627]
data: [ 0.95911429, -0.04577467, -0.27929279,
0.04325362, 0.9989487 , -0.01518615,
0.27969431, 0.00248483, 0.96008589]
projection_matrix:
rows: 3
cols: 4
data: [343.984335, 0.000000, -82.478912, 0.000000, 0.000000, 343.984335, 132.359158, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
data: [ 305.6735 , 0. , 289.60029, 0. ,
0. , 305.6735 , 121.06541, 0. ,
0. , 0. , 1. , 0. ]

26
right_1280x720.yaml Normal file
View File

@ -0,0 +1,26 @@
image_width: 1280
image_height: 720
camera_name: right
camera_matrix:
rows: 3
cols: 3
data: [ 879.81628, 0. , 631.55074,
0. , 877.90835, 349.78586,
0. , 0. , 1. ]
camera_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.359859, 0.129457, 0.002187, 0.006292, 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]
projection_matrix:
rows: 3
cols: 4
data: [ 869.23405, 0. , 590.64311, -46.17111,
0. , 869.23405, 366.70978, 0. ,
0. , 0. , 1. , 0. ]

View File

@ -4,17 +4,23 @@ camera_name: right
camera_matrix:
rows: 3
cols: 3
data: [231.318831, 0.000000, 152.641652, 0.000000, 308.097601, 127.750465, 0.000000, 0.000000, 1.000000]
distortion_model: plumb_bob
data: [ 227.8688 , 0. , 157.95209,
0. , 303.09539, 118.1566 ,
0. , 0. , 1. ]
camera_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.373994, 0.139767, 0.000333, -0.001028, 0.000000]
data: [-0.399746, 0.164662, -0.001467, 0.001856, 0.000000]
rectification_matrix:
rows: 3
cols: 3
data: [0.918165, 0.031804, 0.394919, -0.026285, 0.999467, -0.019379, -0.395324, 0.007413, 0.918512]
data: [ 0.97349106, -0.02827958, -0.2269701 ,
0.03031821, 0.99952516, 0.00550008,
0.22670678, -0.01223561, 0.9738862 ]
projection_matrix:
rows: 3
cols: 4
data: [343.984335, 0.000000, -82.478912, -22.005200, 0.000000, 343.984335, 132.359158, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
data: [ 305.6735 , 0. , 289.60029, -14.70807,
0. , 305.6735 , 121.06541, 0. ,
0. , 0. , 1. , 0. ]

View File

@ -13,6 +13,10 @@
<param name="speckle_size" value="142" />
<param name="texture_threshold" value="1040" />
</node>
<node name="disparity_to_image" pkg="topic_tools" type="transform" output="screen"
args="/stereo/disparity /stereo/disparity_image sensor_msgs/Image 'm.image'">
</node>
</group>

View File

@ -10,7 +10,8 @@
<arg name="width" default="320" /> <!-- Image Width -->
<arg name="height" default="240" /> <!-- Image Height -->
<arg name="fps" default="30" /> <!-- Desired framerate -->
<arg name="calibration_right_file" default="right_320x240.yaml"/>
<arg name="calibration_left_file" default="left_320x240.yaml"/>
<!-- Make arguments available to parameter server -->
<param name="image_width" type="int" value="$(arg width)" />
<param name="image_height" type="int" value="$(arg height)" />
@ -27,7 +28,7 @@
<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/right_320x240.yaml" />
<param name="camera_info_url" value="package://jetson_csi_cam/$(arg calibration_right_file)" />
<!--<param name="image_encoding_" value="jpeg" />-->
<remap from="camera/image_raw" to="right/image_raw" />
<remap from="camera/camera_info" to="right/camera_info" />
@ -43,13 +44,18 @@
<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)" />
<param name="camera_info_url" value="package://jetson_csi_cam/left_320x240.yaml" />
<param name="camera_info_url" value="package://jetson_csi_cam/$(arg calibration_left_file)" />
<!--<param name="image_encoding_" value="jpeg" />-->
<remap from="camera/image_raw" to="left/image_raw" />
<remap from="camera/camera_info" to="left/camera_info" />
<remap from="set_camera_info" to="camera_info" />
</node>
<!--<node pkg="tf" type="static_transform_publisher" name="tf_front_right_camera"
args="0 2.85 0 -1.57 0 -1.57 fcu front_camera_link 10"/>
<node pkg="tf" type="static_transform_publisher" name="tf_front_left_camera"
args="0 -2.85 0 -1.57 0 -1.57 fcu front_camera_link 10"/>-->
</group>
</launch>