diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/compute_path_to_pose_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/compute_path_to_pose_action.hpp
index d610563b0f41631878ace76c2c07efeff20ca54b..c6df35c1aa74ebcae6a8ec6a58a15586890b7479 100644
--- a/nav2_behavior_tree/include/nav2_behavior_tree/compute_path_to_pose_action.hpp
+++ b/nav2_behavior_tree/include/nav2_behavior_tree/compute_path_to_pose_action.hpp
@@ -38,6 +38,7 @@ public:
   void on_tick() override
   {
     getInput("goal", goal_.pose);
+    getInput("planner_property", goal_.planner_property);
   }
 
   void on_success() override
@@ -55,7 +56,8 @@ public:
   {
     return providedBasicPorts({
         BT::OutputPort<nav_msgs::msg::Path>("path", "Path created by ComputePathToPose node"),
-        BT::InputPort<geometry_msgs::msg::PoseStamped>("goal", "Destination to plan to")
+        BT::InputPort<geometry_msgs::msg::PoseStamped>("goal", "Destination to plan to"),
+        BT::InputPort<std::string>("planner_property", "")
       });
   }
 
diff --git a/nav2_bt_navigator/README.md b/nav2_bt_navigator/README.md
index 579af2acedac5f7aca9c83ceaca9838253a9321e..394efd026654edcf46f2a5a8296379149b7e1816 100644
--- a/nav2_bt_navigator/README.md
+++ b/nav2_bt_navigator/README.md
@@ -37,7 +37,7 @@ The BT Navigator package has two sample XML-based descriptions of BTs.  These tr
       <RateController hz="1.0">
         <Fallback>
           <GoalReached/>
-          <ComputePathToPose goal="${goal}"/>
+          <ComputePathToPose goal="${goal}" planner_property="GridBased"/>
         </Fallback>
       </RateController>
       <FollowPath path="${path}"/>
@@ -52,10 +52,10 @@ Navigate with replanning is composed of the following custom decorator, conditio
 * RateController: A custom control flow node, which throttles down the tick rate.  This custom node has only one child and its tick rate is defined with a pre-defined frequency that the user can set.  This node returns RUNNING when it is not ticking its child. Currently, in the navigation, the `RateController` is used to tick the  `ComputePathToPose` and `GoalReached` node at 1 Hz.
 
 #### Condition Nodes
-* GoalReached: Checks the distance to the goal, if the distance to goal is less than the pre-defined threshold, the tree returns SUCCESS, which in that case the `ComputePathToPose` action node will not get ticked. 
+* GoalReached: Checks the distance to the goal, if the distance to goal is less than the pre-defined threshold, the tree returns SUCCESS, which in that case the `ComputePathToPose` action node will not get ticked.
 
 #### Action Nodes
-* ComputePathToPose: When this node is ticked, the goal will be placed on the blackboard which will be shared to the Behavior tree.  The bt action node would then utilizes the action server to send a request to the global planner to recompute the global path.  Once the global path is recomputed, the result will be sent back via action server and then the updated path will be placed on the blackboard.
+* ComputePathToPose: When this node is ticked, the goal will be placed on the blackboard which will be shared to the Behavior tree.  The bt action node would then utilizes the action server to send a request to the global planner to recompute the global path.  Once the global path is recomputed, the result will be sent back via action server and then the updated path will be placed on the blackboard. The `planner` parameter will tell the planning server which of the loaded planning plugins to utilize, in case of desiring different parameters, planners, or behaviors. The name of the planner should correspond with the high level task it accomplishes and align with the `planner_property_names` name given to it in the planner server. If no planner name is provided, it will use the only planner in the planner server when only one is available.
 
 
 The graphical version of this Behavior Tree:
diff --git a/nav2_bt_navigator/behavior_trees/navigate_w_replanning.xml b/nav2_bt_navigator/behavior_trees/navigate_w_replanning.xml
index d4cc01745d3267b1cdccfd3ca0af1ce4eb4b0eae..53fdd642f501c9bac5ff8d04250674317426701c 100644
--- a/nav2_bt_navigator/behavior_trees/navigate_w_replanning.xml
+++ b/nav2_bt_navigator/behavior_trees/navigate_w_replanning.xml
@@ -8,7 +8,7 @@
       <RateController hz="1.0">
         <Fallback>
           <GoalReached/>
-          <ComputePathToPose goal="{goal}"/>
+          <ComputePathToPose goal="{goal}" planner_property="GridBased"/>
         </Fallback>
       </RateController>
       <FollowPath path="{path}"/>
diff --git a/nav2_bt_navigator/behavior_trees/navigate_w_replanning_and_recovery.xml b/nav2_bt_navigator/behavior_trees/navigate_w_replanning_and_recovery.xml
index 4f81bac590006fb9dd9ee9712be4d0866102da9d..eb406607cb9c8e9ea37658663a70614ea43629b7 100644
--- a/nav2_bt_navigator/behavior_trees/navigate_w_replanning_and_recovery.xml
+++ b/nav2_bt_navigator/behavior_trees/navigate_w_replanning_and_recovery.xml
@@ -9,8 +9,8 @@
         <RateController hz="1.0">
           <Fallback name="GoalReached">
             <GoalReached/>
-            <RecoveryNode number_of_retries="1" name="ComputePath">
-              <ComputePathToPose goal="{goal}" path="{path}"/>
+            <RecoveryNode number_of_retries="1" name="ComputePathToPose">
+              <ComputePathToPose goal="{goal}" path="{path}" planner_property="GridBased"/>
               <ClearEntireCostmap service_name="global_costmap/clear_entirely_global_costmap"/>
             </RecoveryNode>
           </Fallback>
diff --git a/nav2_msgs/action/ComputePathToPose.action b/nav2_msgs/action/ComputePathToPose.action
index 0a6b62ee4a6a70a7350aae602565c469821efbc6..40a1b9372465a1f7258dae35946ce7ad8cdbc4c0 100644
--- a/nav2_msgs/action/ComputePathToPose.action
+++ b/nav2_msgs/action/ComputePathToPose.action
@@ -1,5 +1,6 @@
 #goal definition
 geometry_msgs/PoseStamped pose
+string planner_property
 ---
 #result definition
 nav_msgs/Path path
diff --git a/nav2_navfn_planner/src/navfn_planner.cpp b/nav2_navfn_planner/src/navfn_planner.cpp
index 7bd951ec41244daeb633f06aafbc40b3b6defc12..31ee9060580c8e6272b46b12b696f36b7766b8ee 100644
--- a/nav2_navfn_planner/src/navfn_planner.cpp
+++ b/nav2_navfn_planner/src/navfn_planner.cpp
@@ -49,7 +49,8 @@ NavfnPlanner::NavfnPlanner()
 
 NavfnPlanner::~NavfnPlanner()
 {
-  RCLCPP_INFO(node_->get_logger(), "Destroying plugin %s", name_.c_str());
+  RCLCPP_INFO(node_->get_logger(), "Destroying plugin %s of type NavfnPlanner",
+    name_.c_str());
 }
 
 void
@@ -64,7 +65,8 @@ NavfnPlanner::configure(
   costmap_ = costmap_ros->getCostmap();
   global_frame_ = costmap_ros->getGlobalFrameID();
 
-  RCLCPP_INFO(node_->get_logger(), "Configuring plugin %s", name_.c_str());
+  RCLCPP_INFO(node_->get_logger(), "Configuring plugin %s of type NavfnPlanner",
+    name_.c_str());
 
   // Initialize parameters
   // Declare this plugin's parameters
@@ -83,19 +85,22 @@ NavfnPlanner::configure(
 void
 NavfnPlanner::activate()
 {
-  RCLCPP_INFO(node_->get_logger(), "Activating plugin %s", name_.c_str());
+  RCLCPP_INFO(node_->get_logger(), "Activating plugin %s of type NavfnPlanner",
+    name_.c_str());
 }
 
 void
 NavfnPlanner::deactivate()
 {
-  RCLCPP_INFO(node_->get_logger(), "Deactivating plugin %s", name_.c_str());
+  RCLCPP_INFO(node_->get_logger(), "Deactivating plugin %s of type NavfnPlanner",
+    name_.c_str());
 }
 
 void
 NavfnPlanner::cleanup()
 {
-  RCLCPP_INFO(node_->get_logger(), "Cleaning up plugin %s", name_.c_str());
+  RCLCPP_INFO(node_->get_logger(), "Cleaning up plugin %s of type NavfnPlanner",
+    name_.c_str());
   planner_.reset();
 }
 
diff --git a/nav2_planner/README.md b/nav2_planner/README.md
index ec4bb7b460f70bdd68cf5057c48c57ec1eeed2bf..0d4447b103d3d7866ff658b7097448d7cf4b26e7 100644
--- a/nav2_planner/README.md
+++ b/nav2_planner/README.md
@@ -2,4 +2,4 @@
 
 The Nav2 planner is a [planning module](../doc/requirements/requirements.md) that implements the `nav2_behavior_tree::ComputePathToPose` interface.
 
-A planning module implementing the `nav2_behavior_tree::ComputePathToPose` interface is responsible for generating a feasible path given start and end robot poses. It loads a planner plugin like NavFn to do the path generation.
+A planning module implementing the `nav2_behavior_tree::ComputePathToPose` interface is responsible for generating a feasible path given start and end robot poses. It loads a map of potential planner plugins like NavFn to do the path generation in different user-defined situations.
diff --git a/nav2_planner/include/nav2_planner/planner_server.hpp b/nav2_planner/include/nav2_planner/planner_server.hpp
index 31e00bf0a5912e1badb0470ad975293eae31b8f9..23c2f882e47538b5aa18d0ebded575f4e4bfb608 100644
--- a/nav2_planner/include/nav2_planner/planner_server.hpp
+++ b/nav2_planner/include/nav2_planner/planner_server.hpp
@@ -19,6 +19,7 @@
 #include <string>
 #include <memory>
 #include <vector>
+#include <unordered_map>
 
 #include "geometry_msgs/msg/point.hpp"
 #include "geometry_msgs/msg/pose_stamped.hpp"
@@ -55,6 +56,8 @@ public:
    */
   ~PlannerServer();
 
+  using PlannerMap = std::unordered_map<std::string, nav2_core::GlobalPlanner::Ptr>;
+
 protected:
   /**
    * @brief Configure member variables and initializes planner
@@ -101,7 +104,7 @@ protected:
   /**
    * @brief The action server callback which calls planner to get the path
    */
-  void computePathToPose();
+  void computePlan();
 
   /**
    * @brief Publish a path for visualization purposes
@@ -110,9 +113,10 @@ protected:
   void publishPlan(const nav_msgs::msg::Path & path);
 
   // Planner
-  nav2_core::GlobalPlanner::Ptr planner_;
+  PlannerMap planners_;
   pluginlib::ClassLoader<nav2_core::GlobalPlanner> gp_loader_;
-  std::string planner_plugin_name_;
+  std::vector<std::string> plugin_properties_, plugin_types_;
+  std::string planner_properties_concat_;
 
   // TF buffer
   std::shared_ptr<tf2_ros::Buffer> tf_;
@@ -124,6 +128,9 @@ protected:
 
   // Publishers for the path
   rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr plan_publisher_;
+
+  // Whether we've published the single planner warning yet
+  bool single_planner_warning_given_{false};
 };
 
 }  // namespace nav2_planner
diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp
index 79f8e7242bb5626a3406ef9d703e3811b2514f4d..c3bffd497a9baf53ccc2367167fc788755042357 100644
--- a/nav2_planner/src/planner_server.cpp
+++ b/nav2_planner/src/planner_server.cpp
@@ -41,7 +41,11 @@ PlannerServer::PlannerServer()
   RCLCPP_INFO(get_logger(), "Creating");
 
   // Declare this node's parameters
-  declare_parameter("planner_plugin", "nav2_navfn_planner/NavfnPlanner");
+  std::vector<std::string> default_property, default_type;
+  default_property.push_back("GridBased");
+  default_type.push_back("nav2_navfn_planner/NavfnPlanner");
+  declare_parameter("planner_plugin_properties", default_property);
+  declare_parameter("planner_plugin_types", default_type);
 
   // Setup the global costmap
   costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>(
@@ -54,7 +58,10 @@ PlannerServer::PlannerServer()
 PlannerServer::~PlannerServer()
 {
   RCLCPP_INFO(get_logger(), "Destroying");
-  planner_.reset();
+  PlannerMap::iterator it;
+  for (it = planners_.begin(); it != planners_.end(); ++it) {
+    it->second.reset();
+  }
 }
 
 nav2_util::CallbackReturn
@@ -70,27 +77,41 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & state)
 
   tf_ = costmap_ros_->getTfBuffer();
 
-  get_parameter("planner_plugin", planner_plugin_name_);
+  get_parameter("planner_plugin_properties", plugin_properties_);
+  get_parameter("planner_plugin_types", plugin_types_);
   auto node = shared_from_this();
 
-  try {
-    planner_ = gp_loader_.createUniqueInstance(planner_plugin_name_);
-    RCLCPP_INFO(get_logger(), "Created global planner plugin %s",
-      planner_plugin_name_.c_str());
-    planner_->configure(node,
-      gp_loader_.getName(planner_plugin_name_), tf_, costmap_ros_);
-  } catch (const pluginlib::PluginlibException & ex) {
-    RCLCPP_FATAL(get_logger(), "Failed to create global planner. Exception: %s",
-      ex.what());
+  if (plugin_properties_.size() != plugin_types_.size()) {
+    RCLCPP_FATAL(get_logger(),
+      "Planner plugin names and types sizes do not match!");
     exit(-1);
   }
 
+  for (uint i = 0; i != plugin_types_.size(); i++) {
+    try {
+      nav2_core::GlobalPlanner::Ptr planner =
+        gp_loader_.createUniqueInstance(plugin_types_[i]);
+      RCLCPP_INFO(get_logger(), "Created global planner plugin %s of type %s",
+        plugin_properties_[i].c_str(), plugin_types_[i].c_str());
+      planner->configure(node, plugin_properties_[i], tf_, costmap_ros_);
+      planners_.insert({plugin_properties_[i], planner});
+    } catch (const pluginlib::PluginlibException & ex) {
+      RCLCPP_FATAL(get_logger(), "Failed to create global planner. Exception: %s",
+        ex.what());
+      exit(-1);
+    }
+  }
+
+  for (uint i = 0; i != plugin_types_.size(); i++) {
+    planner_properties_concat_ += plugin_properties_[i] + std::string(" ");
+  }
+
   // Initialize pubs & subs
   plan_publisher_ = create_publisher<nav_msgs::msg::Path>("plan", 1);
 
   // Create the action server that we implement with our navigateToPose method
   action_server_ = std::make_unique<ActionServer>(rclcpp_node_, "ComputePathToPose",
-      std::bind(&PlannerServer::computePathToPose, this));
+      std::bind(&PlannerServer::computePlan, this));
 
   return nav2_util::CallbackReturn::SUCCESS;
 }
@@ -103,7 +124,11 @@ PlannerServer::on_activate(const rclcpp_lifecycle::State & state)
   plan_publisher_->on_activate();
   action_server_->activate();
   costmap_ros_->on_activate(state);
-  planner_->activate();
+
+  PlannerMap::iterator it;
+  for (it = planners_.begin(); it != planners_.end(); ++it) {
+    it->second->activate();
+  }
 
   return nav2_util::CallbackReturn::SUCCESS;
 }
@@ -116,7 +141,11 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & state)
   action_server_->deactivate();
   plan_publisher_->on_deactivate();
   costmap_ros_->on_deactivate(state);
-  planner_->deactivate();
+
+  PlannerMap::iterator it;
+  for (it = planners_.begin(); it != planners_.end(); ++it) {
+    it->second->deactivate();
+  }
 
   return nav2_util::CallbackReturn::SUCCESS;
 }
@@ -130,8 +159,15 @@ PlannerServer::on_cleanup(const rclcpp_lifecycle::State & state)
   plan_publisher_.reset();
   tf_.reset();
   costmap_ros_->on_cleanup(state);
-  planner_->cleanup();
-  planner_.reset();
+
+  PlannerMap::iterator it;
+  for (it = planners_.begin(); it != planners_.end(); ++it) {
+    it->second->cleanup();
+  }
+
+  for (it = planners_.begin(); it != planners_.end(); ++it) {
+    it->second.reset();
+  }
 
   return nav2_util::CallbackReturn::SUCCESS;
 }
@@ -151,7 +187,7 @@ PlannerServer::on_shutdown(const rclcpp_lifecycle::State &)
 }
 
 void
-PlannerServer::computePathToPose()
+PlannerServer::computePlan()
 {
   // Initialize the ComputePathToPose goal and result
   auto goal = action_server_->get_current_goal();
@@ -188,11 +224,27 @@ PlannerServer::computePathToPose()
       "(%.2f, %.2f).", start.pose.position.x, start.pose.position.y,
       goal->pose.pose.position.x, goal->pose.pose.position.y);
 
-    result->path = planner_->createPlan(start, goal->pose);
+    if (planners_.find(goal->planner_property) != planners_.end()) {
+      result->path = planners_[goal->planner_property]->createPlan(start, goal->pose);
+    } else {
+      if (planners_.size() == 1 && goal->planner_property.empty()) {
+        if (!single_planner_warning_given_) {
+          single_planner_warning_given_ = true;
+          RCLCPP_WARN(get_logger(), "No planners specified in action call. "
+            "Server will use only plugin %s in server."
+            " This warning will appear once.", planner_properties_concat_.c_str());
+        }
+        result->path = planners_[planners_.begin()->first]->createPlan(start, goal->pose);
+      } else {
+        RCLCPP_ERROR(get_logger(), "planner %s is not a valid planner. "
+          "Planner names are: %s", goal->planner_property.c_str(),
+          planner_properties_concat_.c_str());
+      }
+    }
 
     if (result->path.poses.size() == 0) {
       RCLCPP_WARN(get_logger(), "Planning algorithm %s failed to generate a valid"
-        " path to (%.2f, %.2f)", planner_plugin_name_.c_str(),
+        " path to (%.2f, %.2f)", goal->planner_property.c_str(),
         goal->pose.pose.position.x, goal->pose.pose.position.y);
       // TODO(orduno): define behavior if a preemption is available
       action_server_->terminate_goals();
@@ -212,7 +264,7 @@ PlannerServer::computePathToPose()
     return;
   } catch (std::exception & ex) {
     RCLCPP_WARN(get_logger(), "%s plugin failed to plan calculation to (%.2f, %.2f): \"%s\"",
-      planner_plugin_name_.c_str(), goal->pose.pose.position.x,
+      goal->planner_property.c_str(), goal->pose.pose.position.x,
       goal->pose.pose.position.y, ex.what());
 
     // TODO(orduno): provide information about fail error to parent task,
diff --git a/nav2_system_tests/src/dummy_controller/dummy_controller.cpp b/nav2_system_tests/src/dummy_controller/dummy_controller.cpp
index b5ffc9359e7d6cdb9dfbf4f015809f3ef71046d0..d87b87f8572dd78e33e32f63f34015383b28962a 100644
--- a/nav2_system_tests/src/dummy_controller/dummy_controller.cpp
+++ b/nav2_system_tests/src/dummy_controller/dummy_controller.cpp
@@ -38,7 +38,7 @@ DummyController::DummyController()
   task_server_->setExecuteCallback(
     std::bind(&DummyController::followPath, this, std::placeholders::_1));
 
-  // Start listening for incoming ComputePathToPose task requests
+  // Start listening for incoming ComputePathToPose action server requests
   task_server_->start();
 
   RCLCPP_INFO(get_logger(), "Initialized DummyController");
diff --git a/nav2_system_tests/src/dummy_planner/dummy_planner.cpp b/nav2_system_tests/src/dummy_planner/dummy_planner.cpp
index 9f4f3d57962c1886b8b20b55ee05612864a52cf5..637cc53b93fabde03c19f9e88d1fe89425fd8a62 100644
--- a/nav2_system_tests/src/dummy_planner/dummy_planner.cpp
+++ b/nav2_system_tests/src/dummy_planner/dummy_planner.cpp
@@ -33,7 +33,7 @@ DummyPlanner::DummyPlanner()
   task_server_ =
     std::make_unique<nav2_behavior_tree::ComputePathToPoseTaskServer>(temp_node, false),
   task_server_->setExecuteCallback(
-    std::bind(&DummyPlanner::computePathToPose, this, std::placeholders::_1));
+    std::bind(&DummyPlanner::computePlan, this, std::placeholders::_1));
 
   // Start listening for incoming ComputePathToPose task requests
   task_server_->start();
@@ -47,7 +47,7 @@ DummyPlanner::~DummyPlanner()
 }
 
 void
-DummyPlanner::computePathToPose(const nav2_behavior_tree::ComputePathToPoseCommand::SharedPtr cmd)
+DummyPlanner::computePlan(const nav2_behavior_tree::ComputePathToPoseCommand::SharedPtr cmd)
 {
   RCLCPP_INFO(get_logger(), "Attempting to a find path from (%.2f, %.2f) to "
     "(%.2f, %.2f).", cmd->start.position.x, cmd->start.position.y,
diff --git a/nav2_system_tests/src/planning/README.md b/nav2_system_tests/src/planning/README.md
index 4b76cc6c7392ad7888adc6350056b4c4c4bd8342..6e95d215ba3bb81ccc3b76fca3960f5775b9b51d 100644
--- a/nav2_system_tests/src/planning/README.md
+++ b/nav2_system_tests/src/planning/README.md
@@ -1,7 +1,5 @@
 # Global Planner Component Testing
 
-Component level tests are available that exercise the Planning Module Task Server API ``` nav2_behavior_tree::ComputePathToPoseTaskServer```. The intention is to develop standard tests that can be used across all planners.
-
 A PlannerTester node provides the world representation in the form of a costmap, sends a request to generate a path, and receives and checks the quality of the generated path.
 
 As mentioned above, currently the world is represented as a costmap. Simplified versions of the world model and costmap are used for testing.
diff --git a/nav2_system_tests/src/planning/planner_tester.hpp b/nav2_system_tests/src/planning/planner_tester.hpp
index 3f1d9e52908a70191f68f6211d0df0ea85429c83..ce26d26835b17b5b540dcad727991da9d55ed0ec 100644
--- a/nav2_system_tests/src/planning/planner_tester.hpp
+++ b/nav2_system_tests/src/planning/planner_tester.hpp
@@ -80,7 +80,7 @@ public:
     if (!nav2_util::getCurrentPose(start, *tf_, "map", "base_link", 0.1)) {
       return false;
     }
-    path = planner_->createPlan(start, goal);
+    path = planners_["GridBased"]->createPlan(start, goal);
     return true;
   }