moved camera scan node to nav2 becuase it is used by the nav2 costmap
authorHenrique Scharlau Coelho <henriquescharlaucoelho@gmail.com>
Sun, 24 Dec 2023 17:06:45 +0000 (14:06 -0300)
committerHenrique Scharlau Coelho <henriquescharlaucoelho@gmail.com>
Sun, 24 Dec 2023 17:06:45 +0000 (14:06 -0300)
twil_2dnav/launch/localization_amcl.launch.xml
twil_2dnav/launch/localization_slam_toolbox.launch.xml
twil_2dnav/launch/nav2_navigator.launch.xml

index 36551cb..d695f0c 100644 (file)
@@ -1,13 +1,6 @@
 <launch>
     <arg name="use_sim_time" default="false"/>
 
-    <node name="depthimage_to_laserscan" pkg="depthimage_to_laserscan" exec="depthimage_to_laserscan_node">
-        <remap from="depth" to="/camera/depth/image_raw"/> 
-        <remap from="depth_camera_info" to="/camera/depth/camera_info"/> 
-        <remap from="scan" to="/camera/depth/image_scan"/> 
-        <param name="output_frame" type="str" value="camera_link"/> 
-    </node>
-
     <node pkg="nav2_amcl" exec="amcl" name="amcl">
         <param name="use_sim_time" value="$(var use_sim_time)"/>
         <param from="$(find-pkg-share twil_2dnav)/config/amcl_params.yaml"/>
index 317af47..b2dae96 100644 (file)
@@ -1,13 +1,6 @@
 <launch>
     <arg name="use_sim_time" default="false"/>
 
-    <node name="depthimage_to_laserscan" pkg="depthimage_to_laserscan" exec="depthimage_to_laserscan_node">
-        <remap from="depth" to="/camera/depth/image_raw"/> 
-        <remap from="depth_camera_info" to="/camera/depth/camera_info"/> 
-        <remap from="scan" to="/camera/depth/image_scan"/> 
-        <param name="output_frame" type="str" value="camera_link"/> 
-    </node>
-
     <node pkg="slam_toolbox" exec="async_slam_toolbox_node" name="slam_toolbox">
         <param name="use_sim_time" value="$(var use_sim_time)" />
         <param from="$(find-pkg-share twil_2dnav)/config/slam_toolbox_mapping_params.yaml"/>
index addee59..c541cc4 100644 (file)
         <param name="yaml_filename" value="$(find-pkg-share ufrgs_maps)/map/centenario1.yaml"/>
     </node>
 
+    <node name="depthimage_to_laserscan" pkg="depthimage_to_laserscan" exec="depthimage_to_laserscan_node">
+        <remap from="depth" to="/camera/depth/image_raw"/> 
+        <remap from="depth_camera_info" to="/camera/depth/camera_info"/> 
+        <remap from="scan" to="/camera/depth/image_scan"/> 
+        <param name="output_frame" type="str" value="camera_link"/> 
+    </node>
+
        <include file="$(find-pkg-share twil_2dnav)/launch/localization_$(var localization).launch.xml">
         <arg name="use_sim_time" value="$(var use_sim_time)"/>
        </include>