diff --git a/nav2_mission_executor/CHANGELOG.rst b/nav2_mission_executor/CHANGELOG.rst
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/nav2_mission_executor/CMakeLists.txt b/nav2_mission_executor/CMakeLists.txt
deleted file mode 100644
index b729b22bb2a13481d6b252f3d094a29f0265feb8..0000000000000000000000000000000000000000
--- a/nav2_mission_executor/CMakeLists.txt
+++ /dev/null
@@ -1,71 +0,0 @@
-cmake_minimum_required(VERSION 3.5)
-project(nav2_mission_executor)
-
-find_package(ament_cmake REQUIRED)
-find_package(nav2_common REQUIRED)
-find_package(rclcpp REQUIRED)
-find_package(rclcpp_action REQUIRED)
-find_package(rclcpp_lifecycle REQUIRED)
-find_package(std_msgs REQUIRED)
-find_package(nav2_tasks REQUIRED)
-find_package(nav2_msgs REQUIRED)
-find_package(nav2_util REQUIRED)
-find_package(behaviortree_cpp REQUIRED)
-find_package(geometry_msgs REQUIRED)
-
-nav2_package()
-
-include_directories(
- include
-)
-
-set(executable_name mission_executor)
-
-add_executable(${executable_name}
- src/main.cpp
-)
-
-set(library_name ${executable_name}_core)
-
-add_library(${library_name} SHARED
- src/mission_executor.cpp
- src/execute_mission_behavior_tree.cpp
-)
-
-set(dependencies
- rclcpp
- rclcpp_action
- rclcpp_lifecycle
- std_msgs
- nav2_tasks
- nav2_msgs
- nav2_util
- behaviortree_cpp
- geometry_msgs
-)
-
-ament_target_dependencies(${executable_name}
- ${dependencies}
-)
-
-target_link_libraries(${executable_name} ${library_name})
-
-ament_target_dependencies(${library_name}
- ${dependencies}
-)
-
-install(TARGETS ${executable_name} ${library_name}
- ARCHIVE DESTINATION lib
- LIBRARY DESTINATION lib
- RUNTIME DESTINATION lib/${PROJECT_NAME}
-)
-
-if(BUILD_TESTING)
- find_package(ament_lint_auto REQUIRED)
- ament_lint_auto_find_test_dependencies()
- add_subdirectory(test)
-endif()
-
-ament_export_include_directories(include)
-
-ament_package()
diff --git a/nav2_mission_executor/README.md b/nav2_mission_executor/README.md
deleted file mode 100644
index 4b51d0de535f1db054574d23fac4bf3486c281aa..0000000000000000000000000000000000000000
--- a/nav2_mission_executor/README.md
+++ /dev/null
@@ -1,98 +0,0 @@
-# Mission Executor
-
-The Mission Executor module is a task server that coordinates other tasks. It can be used to direct the activities of multiple robots as well as other, non-navigation and non-robot tasks. This module would typically reside on a central orchestration computer and direct the operation of remote robots.
-
-## Overview
-
-The Mission Executor module is implemented using [Behavior Trees](https://en.wikipedia.org/wiki/Behavior_tree). As detailed in [Michele Colledanchils's doctoral thesis](https://www.diva-portal.org/smash/get/diva2:1078940/FULLTEXT01.pdf), Behavior Trees are a Control Architecture (CA) initially used in the video game industry to control non-player characters and now applied to the control of autonomous robots.
-
-The Mission Executor task server receives a **MissionPlan** and returns whether the plan was successfully executed, failed, or was canceled. The ExecuteMissionTask is defined as follows:
-
-```C++
-namespace nav2_tasks {
-
-using ExecuteMissionCommand = nav2_msgs::msg::MissionPlan;
-using ExecuteMissionResult = std_msgs::msg::Empty;
-
-using ExecuteMissionTaskClient = TaskClient<ExecuteMissionCommand, ExecuteMissionResult>;
-using ExecuteMissionTaskServer = TaskServer<ExecuteMissionCommand, ExecuteMissionResult>;
-
-} // namespace nav2_tasks
-```
-
-NOTE: An Empty message is used in the definition of the task client and server if there is no other data required.
-
-The [mission plan message](https://github.com/ros-planning/navigation2/blob/master/nav2_msgs/msg/MissionPlan.msg) consists of a header and a mission plan string:
-
-```
-std_msgs/Header header
-string mission_plan
-```
-
-The mission plan itself is an XML string that defines a Behavior Tree. For example, the following XML string specifies a sequence of three NavigateToPose actions:
-
-```XML
-<root main_tree_to_execute="MainTree">
- <BehaviorTree ID="MainTree">
- <SequenceStar name="root">
- <NavigateToPose position="10;11;0.0" orientation="0.7071;0;0.7071;0"/>
- <NavigateToPose position="20;21;0.0" orientation="0.7071;0;0.7071;0"/>
- <NavigateToPose position="30;31;0.0" orientation="0.7071;0;0.7071;0"/>
- </SequenceStar>
- </BehaviorTree>
-</root>
-```
-
-## Invoking the MissionExecutor
-
-The MissionExecutor is an implementation of the ExecuteMissionTaskServer interface, so the corresponding ExecuteMissionTaskClient is used to communicate with the task server, like this:
-
-```C++
-// Demonstrate using a task client to invoke the MissionExecutor task
-void invokeMission(rclcpp::Node::SharedPtr node, std::string mission_plan)
-{
- // Create a task client for this particular kind of task
- auto task_client_ = std::make_unique<nav2_tasks::ExecuteMissionTaskClient>(node);
-
- // Create the input and output
- auto cmd = std::make_shared<nav2_tasks::ExecuteMissionCommand>();
- auto result = std::make_shared<nav2_tasks::ExecuteMissionResult>();
-
- // Set the mission_plan field to the XML input
- cmd->mission_plan = mission_plan;
-
- // Send this message to the task server
- task_client_->sendCommand(cmd);
-
- // Loop until the tasks is complete
- for (;; ) {
- // Get the status of the remote task server
- TaskStatus status = task_client_->waitForResult(result, 100ms);
-
- switch (status) {
- case TaskStatus::SUCCEEDED:
- printf("Task succeeded\n");
- return;
-
- case TaskStatus::FAILED:
- printf("Task failed\n");
- return;
-
- case TaskStatus::CANCELED:
- printf("Task cancelled\n");
- return;
-
- case TaskStatus::RUNNING:
- // Continue waiting for task to complete
- break;
-
- default:
- throw std::logic_error("Invalid status value");
- }
- }
-}
-```
-
-## Open Issues
-
-* **Schema definition and XML document validation** - Currently, there is no dynamic validation of incoming XML. The Behavior-Tree.CPP library is using tinyxml2, which doesn't have a validator. Instead, we can create a schema for the Mission Planning-level XML and use build-time validation of the XML input to ensure that it is well-formed and valid.
diff --git a/nav2_mission_executor/include/nav2_mission_executor/execute_mission_behavior_tree.hpp b/nav2_mission_executor/include/nav2_mission_executor/execute_mission_behavior_tree.hpp
deleted file mode 100644
index c9ae565fcb5fb2c9ecf98cbd042d2553d36f7b2d..0000000000000000000000000000000000000000
--- a/nav2_mission_executor/include/nav2_mission_executor/execute_mission_behavior_tree.hpp
+++ /dev/null
@@ -1,32 +0,0 @@
-// Copyright (c) 2018 Intel Corporation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef NAV2_MISSION_EXECUTOR__EXECUTE_MISSION_BEHAVIOR_TREE_HPP_
-#define NAV2_MISSION_EXECUTOR__EXECUTE_MISSION_BEHAVIOR_TREE_HPP_
-
-#include "rclcpp/rclcpp.hpp"
-#include "nav2_tasks/behavior_tree_engine.hpp"
-
-namespace nav2_mission_executor
-{
-
-class ExecuteMissionBehaviorTree : public nav2_tasks::BehaviorTreeEngine
-{
-public:
- ExecuteMissionBehaviorTree();
-};
-
-} // namespace nav2_mission_executor
-
-#endif // NAV2_MISSION_EXECUTOR__EXECUTE_MISSION_BEHAVIOR_TREE_HPP_
diff --git a/nav2_mission_executor/include/nav2_mission_executor/mission_executor.hpp b/nav2_mission_executor/include/nav2_mission_executor/mission_executor.hpp
deleted file mode 100644
index a0f722365fa02ff13556abdb040ba7c93a20ce75..0000000000000000000000000000000000000000
--- a/nav2_mission_executor/include/nav2_mission_executor/mission_executor.hpp
+++ /dev/null
@@ -1,57 +0,0 @@
-// Copyright (c) 2018 Intel Corporation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef NAV2_MISSION_EXECUTOR__MISSION_EXECUTOR_HPP_
-#define NAV2_MISSION_EXECUTOR__MISSION_EXECUTOR_HPP_
-
-#include <memory>
-
-#include "nav2_util/lifecycle_node.hpp"
-#include "nav2_msgs/action/execute_mission.hpp"
-#include "nav2_util/simple_action_server.hpp"
-
-namespace nav2_mission_executor
-{
-
-class MissionExecutor : public nav2_util::LifecycleNode
-{
-public:
- MissionExecutor();
- ~MissionExecutor();
-
-protected:
- // Implement the lifecycle interface
- nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
- nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
- nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
- nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
- nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
- nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & state) override;
-
- using GoalHandle = rclcpp_action::ServerGoalHandle<nav2_msgs::action::ExecuteMission>;
- using ActionServer = nav2_util::SimpleActionServer<nav2_msgs::action::ExecuteMission>;
-
- // Out action server implements the ExecuteMission action
- std::unique_ptr<ActionServer> action_server_;
-
- // The action server callback
- void executeMission(const std::shared_ptr<GoalHandle> goal_handle);
-
- // A regular, non-spinning ROS node that we can use for the Behavior Tree
- rclcpp::Node::SharedPtr client_node_;
-};
-
-} // namespace nav2_mission_executor
-
-#endif // NAV2_MISSION_EXECUTOR__MISSION_EXECUTOR_HPP_
diff --git a/nav2_mission_executor/package.xml b/nav2_mission_executor/package.xml
deleted file mode 100644
index 50a4cb422371175fefcf2855e8b66553bfcfafdc..0000000000000000000000000000000000000000
--- a/nav2_mission_executor/package.xml
+++ /dev/null
@@ -1,43 +0,0 @@
-<?xml version="1.0"?>
-<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
-<package format="3">
- <name>nav2_mission_executor</name>
- <version>0.1.5</version>
- <description>TODO</description>
- <maintainer email="michael.jeronimo@intel.com">Michael Jeronimo</maintainer>
- <license>Apache License 2.0</license>
-
- <buildtool_depend>ament_cmake</buildtool_depend>
-
- <build_depend>rclcpp</build_depend>
- <build_depend>rclcpp_action</build_depend>
- <build_depend>rclcpp_lifecycle</build_depend>
- <build_depend>std_msgs</build_depend>
- <build_depend>nav2_tasks</build_depend>
- <build_depend>nav2_msgs</build_depend>
- <build_depend>nav2_util</build_depend>
- <build_depend>geometry_msgs</build_depend>
- <build_depend>behaviortree_cpp</build_depend>
- <build_depend>nav2_common</build_depend>
-
- <exec_depend>rclcpp</exec_depend>
- <exec_depend>rclcpp_action</exec_depend>
- <exec_depend>rclcpp_lifecycle</exec_depend>
- <exec_depend>std_msgs</exec_depend>
- <exec_depend>nav2_tasks</exec_depend>
- <exec_depend>nav2_msgs</exec_depend>
- <exec_depend>nav2_util</exec_depend>
- <exec_depend>geometry_msgs</exec_depend>
- <exec_depend>behaviortree_cpp</exec_depend>
-
- <test_depend>ament_lint_common</test_depend>
- <test_depend>ament_lint_auto</test_depend>
- <test_depend>ament_cmake_gtest</test_depend>
- <test_depend>ament_cmake_pytest</test_depend>
- <test_depend>launch</test_depend>
- <test_depend>launch_testing</test_depend>
-
- <export>
- <build_type>ament_cmake</build_type>
- </export>
-</package>
diff --git a/nav2_mission_executor/src/execute_mission_behavior_tree.cpp b/nav2_mission_executor/src/execute_mission_behavior_tree.cpp
deleted file mode 100644
index 94eb7bb56c4fd8bdc5d86c050da5d97209cb2719..0000000000000000000000000000000000000000
--- a/nav2_mission_executor/src/execute_mission_behavior_tree.cpp
+++ /dev/null
@@ -1,29 +0,0 @@
-// Copyright (c) 2018 Intel Corporation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#include "nav2_mission_executor/execute_mission_behavior_tree.hpp"
-#include "nav2_tasks/navigate_to_pose_action.hpp"
-
-using namespace std::chrono_literals;
-
-namespace nav2_mission_executor
-{
-
-ExecuteMissionBehaviorTree::ExecuteMissionBehaviorTree()
-{
- // Register our custom action nodes so that they can be included in XML description
- factory_.registerNodeType<nav2_tasks::NavigateToPoseAction>("NavigateToPose");
-}
-
-} // namespace nav2_mission_executor
diff --git a/nav2_mission_executor/src/main.cpp b/nav2_mission_executor/src/main.cpp
deleted file mode 100644
index 5bf839d74393521f454b087b429bad6fe9d7e254..0000000000000000000000000000000000000000
--- a/nav2_mission_executor/src/main.cpp
+++ /dev/null
@@ -1,28 +0,0 @@
-// Copyright (c) 2018 Intel Corporation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#include <memory>
-
-#include "nav2_mission_executor/mission_executor.hpp"
-#include "rclcpp/rclcpp.hpp"
-
-int main(int argc, char ** argv)
-{
- rclcpp::init(argc, argv);
- auto node = std::make_shared<nav2_mission_executor::MissionExecutor>();
- rclcpp::spin(node->get_node_base_interface());
- rclcpp::shutdown();
-
- return 0;
-}
diff --git a/nav2_mission_executor/src/mission_executor.cpp b/nav2_mission_executor/src/mission_executor.cpp
deleted file mode 100644
index 9ebf453d8bbe7268ac65db1d0bef02c18743548f..0000000000000000000000000000000000000000
--- a/nav2_mission_executor/src/mission_executor.cpp
+++ /dev/null
@@ -1,137 +0,0 @@
-// Copyright (c) 2018 Intel Corporation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#include "nav2_mission_executor/mission_executor.hpp"
-
-#include <string>
-#include <memory>
-
-#include "nav2_mission_executor/execute_mission_behavior_tree.hpp"
-
-namespace nav2_mission_executor
-{
-
-MissionExecutor::MissionExecutor()
-: nav2_util::LifecycleNode("mission_executor", "", true)
-{
- RCLCPP_INFO(get_logger(), "Creating");
-}
-
-MissionExecutor::~MissionExecutor()
-{
- RCLCPP_INFO(get_logger(), "Destroying");
-}
-
-nav2_util::CallbackReturn
-MissionExecutor::on_configure(const rclcpp_lifecycle::State & /*state*/)
-{
- RCLCPP_INFO(get_logger(), "Configuring");
-
- client_node_ = std::make_shared<rclcpp::Node>("mission_executor_client_node");
-
- // Create the action server that we implement with our executeMission method
- action_server_ = std::make_unique<ActionServer>(rclcpp_node_, "ExecuteMission",
- std::bind(&MissionExecutor::executeMission, this, std::placeholders::_1));
-
- return nav2_util::CallbackReturn::SUCCESS;
-}
-
-nav2_util::CallbackReturn
-MissionExecutor::on_activate(const rclcpp_lifecycle::State & /*state*/)
-{
- RCLCPP_INFO(get_logger(), "Activating");
- return nav2_util::CallbackReturn::SUCCESS;
-}
-
-nav2_util::CallbackReturn
-MissionExecutor::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
-{
- RCLCPP_INFO(get_logger(), "Deactivating");
- return nav2_util::CallbackReturn::SUCCESS;
-}
-
-nav2_util::CallbackReturn
-MissionExecutor::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
-{
- RCLCPP_INFO(get_logger(), "Cleaning up");
-
- client_node_.reset();
- action_server_.reset();
-
- return nav2_util::CallbackReturn::SUCCESS;
-}
-
-nav2_util::CallbackReturn
-MissionExecutor::on_error(const rclcpp_lifecycle::State & /*state*/)
-{
- RCLCPP_FATAL(get_logger(), "Lifecycle node entered error state");
- return nav2_util::CallbackReturn::SUCCESS;
-}
-
-nav2_util::CallbackReturn
-MissionExecutor::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
-{
- RCLCPP_INFO(get_logger(), "Shutting down");
- return nav2_util::CallbackReturn::SUCCESS;
-}
-
-void
-MissionExecutor::executeMission(const std::shared_ptr<GoalHandle> goal_handle)
-{
- // Initialize the goal and result
- auto goal = goal_handle->get_goal();
- auto result = std::make_shared<nav2_msgs::action::ExecuteMission::Result>();
-
- // Get a convenient reference to the mission plan string
- const std::string & xml_string = goal->mission_plan.mission_plan;
- RCLCPP_INFO(get_logger(), "Executing mission plan: %s", xml_string.c_str());
-
- // Create the blackboard that will be shared by all of the nodes in the tree
- BT::Blackboard::Ptr blackboard = BT::Blackboard::create<BT::BlackboardLocal>();
-
- // Set a couple values on the blackboard that all of the nodes require
- blackboard->set<rclcpp::Node::SharedPtr>("node", client_node_); // NOLINT
- blackboard->set<std::chrono::milliseconds>("node_loop_timeout", // NOLINT
- std::chrono::milliseconds(100));
-
- // Create the Behavior Tree for this mission
- ExecuteMissionBehaviorTree bt;
-
- // Run the Behavior Tree
- auto is_canceling = [goal_handle]() -> bool {return goal_handle->is_canceling();};
- nav2_tasks::BtStatus rc = bt.run(blackboard, xml_string, is_canceling);
-
- // Handle the result
- switch (rc) {
- case nav2_tasks::BtStatus::SUCCEEDED:
- RCLCPP_INFO(get_logger(), "Mission succeeded");
- goal_handle->succeed(result);
- return;
-
- case nav2_tasks::BtStatus::FAILED:
- RCLCPP_ERROR(get_logger(), "Mission failed");
- goal_handle->abort(result);
- return;
-
- case nav2_tasks::BtStatus::CANCELED:
- RCLCPP_INFO(get_logger(), "Mission canceled");
- goal_handle->canceled(result);
- return;
-
- default:
- throw std::logic_error("Invalid status return from BT");
- }
-}
-
-} // namespace nav2_mission_executor
diff --git a/nav2_mission_executor/test/CMakeLists.txt b/nav2_mission_executor/test/CMakeLists.txt
deleted file mode 100644
index 16300635510bfa8c2b6b0738d4eabeb4b09b025e..0000000000000000000000000000000000000000
--- a/nav2_mission_executor/test/CMakeLists.txt
+++ /dev/null
@@ -1,3 +0,0 @@
-ament_add_gtest(test_mission_executor test_mission_executor.cpp)
-ament_target_dependencies(test_mission_executor ${dependencies})
-target_link_libraries(test_mission_executor ${library_name})
diff --git a/nav2_mission_executor/test/test_mission_executor.cpp b/nav2_mission_executor/test/test_mission_executor.cpp
deleted file mode 100644
index a51a65af1bd6be26f7fce9313b5185925534403b..0000000000000000000000000000000000000000
--- a/nav2_mission_executor/test/test_mission_executor.cpp
+++ /dev/null
@@ -1,88 +0,0 @@
-// Copyright (c) 2018 Intel Corporation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#include <memory>
-
-// #include "gtest/gtest.h"
-#include "nav2_msgs/action/execute_mission.hpp"
-#include "rclcpp/rclcpp.hpp"
-#include "rclcpp_action/rclcpp_action.hpp"
-
-static const char xml_text[] =
- R"(
-<root main_tree_to_execute="MainTree">
- <BehaviorTree ID="MainTree">
- <Sequence name="root">
- <NavigateToPose position="1;2;0" orientation="0;0;0;1"/>
- </Sequence>
- </BehaviorTree>
-</root>
-)";
-
-int main(int argc, char ** argv)
-{
- rclcpp::init(argc, argv);
-
- auto node = std::make_shared<rclcpp::Node>("mission_executor_test_node");
- auto action_client =
- rclcpp_action::create_client<nav2_msgs::action::ExecuteMission>(node, "ExecuteMission");
-
- action_client->wait_for_action_server();
-
- // The goal contains the XML representation of the BT
- auto goal = nav2_msgs::action::ExecuteMission::Goal();
- goal.mission_plan.mission_plan = xml_text;
-
- // Send the goal
- auto future_goal_handle = action_client->async_send_goal(goal);
- if (rclcpp::spin_until_future_complete(node, future_goal_handle) !=
- rclcpp::executor::FutureReturnCode::SUCCESS)
- {
- RCLCPP_ERROR(node->get_logger(), "send goal call failed");
- return 1;
- }
-
- auto goal_handle = future_goal_handle.get();
- if (!goal_handle) {
- RCLCPP_ERROR(node->get_logger(), "Goal was rejected by server");
- return 1;
- }
-
- // Wait for the result
- auto future_result = goal_handle->async_result();
- if (rclcpp::spin_until_future_complete(node, future_result) !=
- rclcpp::executor::FutureReturnCode::SUCCESS)
- {
- RCLCPP_ERROR(node->get_logger(), "get result call failed");
- return 1;
- }
-
- auto wrapped_result = future_result.get();
- int rc = 0;
-
- switch (wrapped_result.code) {
- case rclcpp_action::ResultCode::SUCCEEDED:
- break;
-
- case rclcpp_action::ResultCode::ABORTED:
- case rclcpp_action::ResultCode::CANCELED:
- default:
- RCLCPP_ERROR(node->get_logger(), "Mission failed");
- rc = 1;
- break;
- }
-
- rclcpp::shutdown();
- return rc;
-}
diff --git a/nav2_msgs/CMakeLists.txt b/nav2_msgs/CMakeLists.txt
index 28b5bdec1a37d0b24e293dd9eea1fb788c189041..91808b435af4fe3a44744280be8c902b96af9208 100644
--- a/nav2_msgs/CMakeLists.txt
+++ b/nav2_msgs/CMakeLists.txt
@@ -14,7 +14,6 @@ nav2_package()
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/Costmap.msg"
"msg/CostmapMetaData.msg"
- "msg/MissionPlan.msg"
"msg/Path.msg"
"msg/VoxelGrid.msg"
"srv/GetCostmap.srv"
@@ -23,7 +22,6 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"srv/ClearEntireCostmap.srv"
"action/BackUp.action"
"action/ComputePathToPose.action"
- "action/ExecuteMission.action"
"action/FollowPath.action"
"action/NavigateToPose.action"
"action/Spin.action"
diff --git a/nav2_msgs/action/ExecuteMission.action b/nav2_msgs/action/ExecuteMission.action
deleted file mode 100644
index 3d3e357854b5604e511affb37a3408880ccc44ec..0000000000000000000000000000000000000000
--- a/nav2_msgs/action/ExecuteMission.action
+++ /dev/null
@@ -1,7 +0,0 @@
-#goal definition
-nav2_msgs/MissionPlan mission_plan
----
-#result definition
-std_msgs/Empty result
----
-#feedback
diff --git a/nav2_msgs/msg/MissionPlan.msg b/nav2_msgs/msg/MissionPlan.msg
deleted file mode 100644
index 690b4e8f6f71a3365fea7d6701e0f3ffafb7fdcb..0000000000000000000000000000000000000000
--- a/nav2_msgs/msg/MissionPlan.msg
+++ /dev/null
@@ -1,2 +0,0 @@
-std_msgs/Header header
-string mission_plan
diff --git a/nav2_tasks/include/nav2_tasks/execute_mission_action.hpp b/nav2_tasks/include/nav2_tasks/execute_mission_action.hpp
deleted file mode 100644
index 62cb00d8abcdd99f0339d27238f72bfedf77f40d..0000000000000000000000000000000000000000
--- a/nav2_tasks/include/nav2_tasks/execute_mission_action.hpp
+++ /dev/null
@@ -1,28 +0,0 @@
-// Copyright (c) 2018 Intel Corporation
-//
-// Licensed under the Apache License, Version 2.0 (the "License");
-// you may not use this file except in compliance with the License.
-// You may obtain a copy of the License at
-//
-// http://www.apache.org/licenses/LICENSE-2.0
-//
-// Unless required by applicable law or agreed to in writing, software
-// distributed under the License is distributed on an "AS IS" BASIS,
-// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-// See the License for the specific language governing permissions and
-// limitations under the License.
-
-#ifndef NAV2_TASKS__EXECUTE_MISSION_ACTION_HPP_
-#define NAV2_TASKS__EXECUTE_MISSION_ACTION_HPP_
-
-#include "nav2_tasks/bt_action_node.hpp"
-#include "nav2_tasks/execute_mission_task.hpp"
-
-namespace nav2_tasks
-{
-
-using ExecuteMissionAction = BtActionNode<ExecuteMissionCommand, ExecuteMissionResult>;
-
-} // namespace nav2_tasks
-
-#endif // NAV2_TASKS__EXECUTE_MISSION_ACTION_HPP_
diff --git a/navigation2/package.xml b/navigation2/package.xml
index 42050cbef3bad5364e66a744ab75613810a5521f..e4fe5f2d6f9566b53ba97c377a5f14eac03e0e77 100644
--- a/navigation2/package.xml
+++ b/navigation2/package.xml
@@ -19,7 +19,6 @@
<exec_depend>nav2_dwb_controller</exec_depend>
<exec_depend>nav2_lifecycle_manager</exec_depend>
<exec_depend>nav2_map_server</exec_depend>
- <exec_depend>nav2_mission_executor</exec_depend>
<exec_depend>nav2_motion_primitives</exec_depend>
<exec_depend>nav2_msgs</exec_depend>
<exec_depend>nav2_navfn_planner</exec_depend>
diff --git a/tools/run_test_suite.bash b/tools/run_test_suite.bash
index 63e7a78f781fba1a2a08f2042e40fb68ac812c37..4e0b14be6c4aee1b4daeab1e3204cf0ab3c26cff 100755
--- a/tools/run_test_suite.bash
+++ b/tools/run_test_suite.bash
@@ -7,7 +7,7 @@ SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" # gets the direc
# Skip flaky tests. Nav2 system tests will be run later.
colcon test --packages-skip nav2_system_tests nav2_dynamic_params nav2_motion_primitives \
nav2_bt_navigator nav2_costmap_2d nav2_lifecycle_manager \
- nav2_mission_executor nav2_tasks nav2_robot
+ nav2_tasks nav2_robot
# run the stable tests in nav2_dynamic_params
colcon test --packages-select nav2_dynamic_params --ctest-args --exclude-regex "test_dynamic_params_client"