Skip to content

Commit

Permalink
update launches and add water calibration
Browse files Browse the repository at this point in the history
  • Loading branch information
plnegre committed Jul 10, 2020
1 parent e767ea6 commit 7a186d4
Show file tree
Hide file tree
Showing 7 changed files with 75 additions and 6 deletions.
20 changes: 20 additions & 0 deletions prosilica_camera/config/calibration_water_left.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
image_width: 968
image_height: 728
camera_name: left_optical
camera_matrix:
rows: 3
cols: 3
data: [735.466017, 0.000000, 495.728591, 0.000000, 737.152024, 344.800009, 0.000000, 0.000000, 1.000000]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [0.276054, 0.598468, -0.006349, 0.003771, 0.000000]
rectification_matrix:
rows: 3
cols: 3
data: [0.988383, 0.038607, -0.146997, -0.040079, 0.999172, -0.007065, 0.146602, 0.012874, 0.989112]
projection_matrix:
rows: 3
cols: 4
data: [1159.146375, 0.000000, 633.266916, 0.000000, 0.000000, 1159.146375, 355.930935, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
20 changes: 20 additions & 0 deletions prosilica_camera/config/calibration_water_right.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
image_width: 968
image_height: 728
camera_name: right_optical
camera_matrix:
rows: 3
cols: 3
data: [741.843119, 0.000000, 480.284378, 0.000000, 742.310585, 368.801948, 0.000000, 0.000000, 1.000000]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [0.231310, 0.946365, 0.010306, -0.006880, 0.000000]
rectification_matrix:
rows: 3
cols: 3
data: [0.984522, 0.058527, -0.165202, -0.056866, 0.998273, 0.014771, 0.165781, -0.005148, 0.986149]
projection_matrix:
rows: 3
cols: 4
data: [1159.146375, 0.000000, 633.266916, -164.538649, 0.000000, 1159.146375, 355.930935, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
9 changes: 9 additions & 0 deletions prosilica_camera/launch/mono_left.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<launch>
<rosparam command="load" file="$(find prosilica_camera)/config/stereo_down.yaml"/>
<include file="$(find prosilica_camera)/launch/prosilica_camera_base.launch">
<arg name="camera_ns" value="/stereo_down" />
<arg name="camera_name" value="left" />
<arg name="ip_address" value="10.0.2.2" /> <!-- 192.168.1.80 -->
<arg name="frame_id" value="/stereo_down/left_optical" />
</include>
</launch>
9 changes: 9 additions & 0 deletions prosilica_camera/launch/mono_right.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<launch>
<rosparam command="load" file="$(find prosilica_camera)/config/stereo_down.yaml"/>
<include file="$(find prosilica_camera)/launch/prosilica_camera_base.launch">
<arg name="camera_ns" value="/stereo_down" />
<arg name="camera_name" value="right"/>
<arg name="ip_address" value="10.0.3.2" /> <!-- 192.168.1.81 -->
<arg name="frame_id" value="/stereo_down/left_optical" />
</include>
</launch>
11 changes: 11 additions & 0 deletions prosilica_camera/launch/stereo_calibration.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<launch>
<arg name="stereo" default="stereo_down" />
<node pkg="camera_calibration" type="cameracalibrator.py" name="camera_calibrator"
args="--approximate=0.1 --size 6x8 --square=0.04" output="screen">

<remap from="left" to="$(arg stereo)/left/image_raw" />
<remap from="left_camera" to="$(arg stereo)/left" />
<remap from="right" to="$(arg stereo)/right/image_raw" />
<remap from="right_camera" to="$(arg stereo)/right" />
</node>
</launch>
8 changes: 4 additions & 4 deletions prosilica_camera/launch/stereo_down.launch
Original file line number Diff line number Diff line change
@@ -1,23 +1,23 @@
<launch>
<arg name="processing" default="true"/>
<arg name="processing" default="false"/>
<arg name="stereo" default="stereo_down" />

<rosparam command="load" file="$(find prosilica_camera)/config/stereo_down.yaml"/>
<include file="$(find prosilica_camera)/launch/prosilica_camera_base.launch">
<arg name="camera_ns" value="$(arg stereo)" />
<arg name="camera_name" value="left" />
<arg name="ip_address" value="192.168.1.80" />
<arg name="ip_address" value="10.0.2.2" /> <!-- 192.168.1.80 -->
<arg name="frame_id" value="/stereo_down/left_optical" />
</include>
<include file="$(find prosilica_camera)/launch/prosilica_camera_base.launch">
<arg name="camera_ns" value="$(arg stereo)" />
<arg name="camera_name" value="right" />
<arg name="ip_address" value="192.168.1.81" />
<arg name="ip_address" value="10.0.3.2" /> <!-- 192.168.1.81 -->
<arg name="frame_id" value="/stereo_down/right_optical" />
</include>

<node if="$(arg processing)" ns="$(arg stereo)" pkg="stereo_image_proc" type="stereo_image_proc" name="stereo_image_proc" respawn="true" output="screen">
<rosparam file="$(find prosilica_camera)/config/disparity_params_$(arg stereo).yaml"/>
</node>

</launch>
</launch>
4 changes: 2 additions & 2 deletions prosilica_camera/launch/stereo_pipeline.launch
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<launch>

<arg name="stereo" />
<arg name="enable_decimate_x2" default="true"/>
<arg name="enable_decimate_x2" default="false"/>
<arg name="enable_decimate_x4" default="false"/>
<arg name="launch_in_nuc" default="true"/>

Expand Down Expand Up @@ -36,4 +36,4 @@
</group>


</launch>
</launch>

0 comments on commit 7a186d4

Please sign in to comment.