From aa5e30ed88761727e587dccd1c65cc0bebad939a Mon Sep 17 00:00:00 2001
From: asantamaria <asantamaria@iri.upc.edu>
Date: Mon, 19 Dec 2016 10:31:01 +0100
Subject: [PATCH] First version with MV parameters working fine.

---
 launch/iri_mvbluefox3_camera.launch | 6 +++---
 params/F0300123_calib.yaml          | 7 +++----
 params/F0300141_calib.yaml          | 7 +++----
 3 files changed, 9 insertions(+), 11 deletions(-)

diff --git a/launch/iri_mvbluefox3_camera.launch b/launch/iri_mvbluefox3_camera.launch
index 1ba4f84..9653d40 100644
--- a/launch/iri_mvbluefox3_camera.launch
+++ b/launch/iri_mvbluefox3_camera.launch
@@ -1,7 +1,7 @@
 <!--DOCTYPE html-->
 <launch>
 
-  <arg name="num_cams" default="2" />
+  <arg name="num_cams" default="1" />
 
   <arg name="c1_name" default="cam1" />
   <arg name="c1_serial" default="F0300141" />
@@ -46,8 +46,8 @@
     <remap from="/image" to="/iri_mvbluefox3_camera/$(arg c1_name)/image_raw"/>
   </node>
 
-  <node pkg="image_view" type="image_view" name="image_view_$(arg c2_name)" >
+<!--   <node pkg="image_view" type="image_view" name="image_view_$(arg c2_name)" >
     <remap from="/image" to="/iri_mvbluefox3_camera/$(arg c2_name)/image_raw"/>
-  </node>  
+  </node>   -->
 
 </launch>
diff --git a/params/F0300123_calib.yaml b/params/F0300123_calib.yaml
index f233f44..514d103 100644
--- a/params/F0300123_calib.yaml
+++ b/params/F0300123_calib.yaml
@@ -4,12 +4,12 @@ camera_name: camera
 camera_matrix:
   rows: 3
   cols: 3
-  data: [1280, 0, 960, 0, 1280, 960, 0, 0, 1]
+  data: [976.915955, 0, 582.117763, 0, 977.821859, 440.568838, 0, 0, 1]
 distortion_model: plumb_bob
 distortion_coefficients:
   rows: 1
   cols: 5
-  data: [0, 0, 0, 0, 0]
+  data: [-0.103886, 0.096744, -0.001615, -0.000599, 0.000000]
 rectification_matrix:
   rows: 3
   cols: 3
@@ -17,5 +17,4 @@ rectification_matrix:
 projection_matrix:
   rows: 3
   cols: 4
-  data: [1280, 0, 960, 0, 0, 1280, 960, 0, 0, 0, 1, 0]
-  
\ No newline at end of file
+  data: [953.288513, 0, 582.082677, 0, 0, 956.783997, 437.916171, 0, 0, 0, 1, 0]
\ No newline at end of file
diff --git a/params/F0300141_calib.yaml b/params/F0300141_calib.yaml
index f233f44..0d383a3 100644
--- a/params/F0300141_calib.yaml
+++ b/params/F0300141_calib.yaml
@@ -4,12 +4,12 @@ camera_name: camera
 camera_matrix:
   rows: 3
   cols: 3
-  data: [1280, 0, 960, 0, 1280, 960, 0, 0, 1]
+  data: [978.052122, 0, 673.891465, 0, 977.902574, 396.562028, 0, 0, 1]
 distortion_model: plumb_bob
 distortion_coefficients:
   rows: 1
   cols: 5
-  data: [0, 0, 0, 0, 0]
+  data: [-0.113653, 0.104639, -0.000432, -0.000599, 0.000000]
 rectification_matrix:
   rows: 3
   cols: 3
@@ -17,5 +17,4 @@ rectification_matrix:
 projection_matrix:
   rows: 3
   cols: 4
-  data: [1280, 0, 960, 0, 0, 1280, 960, 0, 0, 0, 1, 0]
-  
\ No newline at end of file
+  data: [953.769836, 0, 670.897749, 0, 0, 957.995728, 394.725275, 0, 0, 0, 1, 0]
\ No newline at end of file
-- 
GitLab