From 90489f8aeed32db90c61d17f6c8875df3c02457a Mon Sep 17 00:00:00 2001
From: Sergi Hernandez Juan <shernand@iri.upc.edu>
Date: Wed, 11 May 2022 19:59:21 +0200
Subject: [PATCH] Added two new arguments to specify the local and global
 planner configuration files.

---
 launch/include/move_base.launch | 6 ++++--
 launch/nav.launch               | 4 ++++
 2 files changed, 8 insertions(+), 2 deletions(-)

diff --git a/launch/include/move_base.launch b/launch/include/move_base.launch
index 0721ea6..94c2e3f 100644
--- a/launch/include/move_base.launch
+++ b/launch/include/move_base.launch
@@ -14,7 +14,9 @@
   <arg name="odom_topic"               default="/$(arg ns)/odom"/>
   <arg name="cmd_vel_topic"            default="/$(arg ns)/navigation/cmd_vel"/>
   <arg name="local_planner"            default="dwa"/>
+  <arg name="local_planner_params"     default="dwa_params.yaml"/>
   <arg name="global_planner"           default="global_planner"/>
+  <arg name="global_planner_params"    default="global_planner_params.yaml"/>
   <arg name="costmap_path"             value="map"    if="$(arg use_map)"/>
   <arg name="costmap_path"             value="no_map" unless="$(arg use_map)"/>
   <arg name="output"                   default="screen" />
@@ -34,8 +36,8 @@
       <remap from="move_base"    to="$(arg move_base_name)" />
 
       <rosparam file="$(arg path)/$(arg move_base_params)"                                  command="load" />
-      <rosparam file="$(arg path)/local_planner/$(arg local_planner)_params.yaml"           command="load" />
-      <rosparam file="$(arg path)/global_planner/$(arg global_planner)_params.yaml"         command="load" />
+      <rosparam file="$(arg path)/local_planner/$(arg local_planner_params)"                command="load" />
+      <rosparam file="$(arg path)/global_planner/$(arg global_planner_params)"              command="load" />
 
       <rosparam file="$(arg path)/costmap/$(arg costmap_common_params)"                     command="load" ns="local_costmap" />
       <rosparam file="$(arg path)/costmap/$(arg costmap_local_params)"                      command="load" ns="local_costmap"/>
diff --git a/launch/nav.launch b/launch/nav.launch
index 89e2a57..68cf3e6 100644
--- a/launch/nav.launch
+++ b/launch/nav.launch
@@ -32,7 +32,9 @@
     <arg name="resolution"               default="0.1"/>
   <arg name="use_move_base"              default="true"/>
     <arg name="local_planner"            default="dwa"/>
+    <arg name="local_planner_params"     default="dwa_params.yaml"/>
     <arg name="global_planner"           default="global_planner"/>
+    <arg name="global_planner_params"    default="global_planner_params.yaml"/>
   <arg name="output"                     default="screen" />
   <arg name="launch_prefix"              default="" />
 
@@ -126,7 +128,9 @@
       <arg name="odom_topic"               value="$(arg odom_topic)"/>
       <arg name="cmd_vel_topic"            value="$(arg cmd_vel_topic)"/>
       <arg name="local_planner"            value="$(arg local_planner)"/>
+      <arg name="local_planner_params"     value="$(arg local_planner_params)"/>
       <arg name="global_planner"           value="$(arg global_planner)"/>
+      <arg name="global_planner_params"    value="$(arg global_planner_params)"/>
       <arg name="output"                   value="$(arg output)" />
       <arg name="launch_prefix"            value="$(arg launch_prefix)" />
     </include>
-- 
GitLab