From ba4f98bbf9ad966c187d073c8e591d5c9b70abd2 Mon Sep 17 00:00:00 2001
From: Alopez <alopez@iri.upc.edu>
Date: Mon, 17 May 2021 17:39:38 +0200
Subject: [PATCH] Added image_proc crop

---
 config/adc_common/crop_front_image.yaml |  2 ++
 launch/adc_global_localization.launch   | 19 +++++++++++++++----
 2 files changed, 17 insertions(+), 4 deletions(-)
 create mode 100644 config/adc_common/crop_front_image.yaml

diff --git a/config/adc_common/crop_front_image.yaml b/config/adc_common/crop_front_image.yaml
new file mode 100644
index 0000000..2f013ee
--- /dev/null
+++ b/config/adc_common/crop_front_image.yaml
@@ -0,0 +1,2 @@
+y_offset: 480
+height: 320
diff --git a/launch/adc_global_localization.launch b/launch/adc_global_localization.launch
index bef79cc..f91451c 100644
--- a/launch/adc_global_localization.launch
+++ b/launch/adc_global_localization.launch
@@ -33,8 +33,8 @@
       <param name="max_track_error"       type="double" value="0.2" />
       <param name="marker_margin"         type="double" value="1.0" />
       <param name="output_frame"          type="string" value="$(arg car_name)/front_camera_uvc_camera_optical" />
-      <remap from="/$(arg car_name)/camera_image"     to="/$(arg car_name)/sensors/basler_camera/inverted_image_raw" />
-      <remap from="/$(arg car_name)/camera_info"      to="/$(arg car_name)/sensors/basler_camera/camera_info" />
+      <remap from="/$(arg car_name)/camera_image"     to="/$(arg car_name)/sensors/basler_camera_cropped/inverted_image_raw" />
+      <remap from="/$(arg car_name)/camera_info"      to="/$(arg car_name)/sensors/basler_camera_cropped/camera_info" />
       <remap from="/$(arg car_name)/ar_pose_marker"   to="/$(arg car_name)/ar_pose_marker" />
     </node>
 
@@ -51,10 +51,21 @@
       <arg name="node_name"         value="iri_image_inverter"/>
       <arg name="output"            value="$(arg output)"/>
       <arg name="launch_prefix"     value="$(arg launch_prefix)"/>
-      <arg name="image_in_topic"    value="/$(arg car_name)/sensors/basler_camera/image_raw"/>
-      <arg name="image_out_topic"   value="/$(arg car_name)/sensors/basler_camera/inverted_image_raw"/>
+      <arg name="image_in_topic"    value="/$(arg car_name)/sensors/basler_camera_cropped/image_raw"/>
+      <arg name="image_out_topic"   value="/$(arg car_name)/sensors/basler_camera_cropped/inverted_image_raw"/>
     </include>
 
+    <node pkg="nodelet" type="nodelet" name="standalone_nodelet"  args="manager"/>
+
+    <node name="crop_image"
+          pkg="nodelet"
+          type="nodelet" 
+          args="load image_proc/crop_decimate standalone_nodelet">
+      <remap from="camera" to="/$(arg car_name)/sensors/basler_camera"/>
+      <remap from="camera_out" to="/$(arg car_name)/sensors/basler_camera_cropped"/>
+      <rosparam file="$(find iri_adc_launch)/config/adc_common/crop_front_image.yaml" command="load"/>
+    </node>
+
     <include file="$(find iri_adc_landmarks_slam_solver)/launch/node.launch">
       <arg name="node_name"                  value="iri_adc_landmarks_slam_solver"/>
       <arg name="output"                     value="$(arg output)"/>
-- 
GitLab