--- /dev/null
+<launch>
+ <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"/>
+ </node>
+
+ <node pkg="nav2_lifecycle_manager" exec="lifecycle_manager" name="lifecycle_manager_nav2">
+ <param name="use_sim_time" value="$(var use_sim_time)"/>
+ <param name="autostart" value="$(var autostart)"/>
+ <param name="node_names" value="[
+ 'map_server',
+ 'amcl',
+ 'controller_server',
+ 'planner_server',
+ 'behavior_server',
+ 'bt_navigator']"/>
+ </node>
+</launch>
+
<arg name="map" default="$(find-pkg-share ufrgs_maps)/map/centenario1.yaml"/>
<arg name="autostart" default="true"/>
<arg name="controller" default=""/>
+ <arg name="localization" default="amcl"/>
<node pkg="nav2_map_server" name="map_server" exec="map_server">
<param name="use_sim_time" value="$(var use_sim_time)"/>
<remap from="cmd_vel" to="$(var controller)/command"/>
</node>
+
<node pkg="nav2_bt_navigator" exec="bt_navigator" name="bt_navigator">
<param name="use_sim_time" value="$(var use_sim_time)"/>
<param from="$(find-pkg-share twil_2dnav)/config/bt_navigator_params.yaml"/>
<remap from="odom" to="$(var controller)/odom"/>
</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"/>
- </node>
-
- <node pkg="nav2_lifecycle_manager" exec="lifecycle_manager" name="lifecycle_manager_nav2">
- <param name="use_sim_time" value="$(var use_sim_time)"/>
- <param name="autostart" value="$(var autostart)"/>
- <param name="node_names" value="[
- 'map_server',
- 'amcl',
- 'controller_server',
- 'planner_server',
- 'behavior_server',
- 'bt_navigator']"/>
- </node>
-
- <node pkg="robot_localization" exec="ekf_node" name="ekf_filter_node" output="screen">
+ <node pkg="robot_localization" exec="ekf_node" name="ekf_filter_node">
<param name="use_sim_time" value="$(var use_sim_time)"/>
<param name="odom0" value="$(var controller)/odom"/>
<param from="$(find-pkg-share twil_2dnav)/config/ekf_params.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">
+ </include>
</launch>