diff --git a/nav2_core/CMakeLists.txt b/nav2_core/CMakeLists.txt
index c8d15ac9d3228ada4d95e34c92d59b317bb70fad..c028762046431dca0d53ac8da6674e6484dba7fc 100644
--- a/nav2_core/CMakeLists.txt
+++ b/nav2_core/CMakeLists.txt
@@ -6,9 +6,12 @@ find_package(nav2_costmap_2d REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
+find_package(nav2_util REQUIRED)
+find_package(nav_msgs REQUIRED)
install(DIRECTORY include/
DESTINATION include/
)
+ament_export_include_directories(include)
ament_package()
diff --git a/nav2_core/include/nav2_core/global_planner.hpp b/nav2_core/include/nav2_core/global_planner.hpp
index 92d28ea40db1930268db52ca4e3585b48b4e1983..eef65d9046ee12d3975a8a9e32b27288d20da58c 100644
--- a/nav2_core/include/nav2_core/global_planner.hpp
+++ b/nav2_core/include/nav2_core/global_planner.hpp
@@ -12,15 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef NAV2_CORE_GLOBAL_PLANNER_H_
-#define NAV2_CORE_GLOBAL_PLANNER_H_
+#ifndef NAV2_CORE__GLOBAL_PLANNER_H_
+#define NAV2_CORE__GLOBAL_PLANNER_H_
#include <string>
-#include "rclcpp/rclcpp.h"
-#include "nav2_costmap_2d/nav2_costmap_2d.hpp"
-#include "tf2_ros/Buffer.h"
-#include "nav_msgs/msg/path.h"
-#include "geometry_msgs/msg/pose_stamped.h"
+#include "rclcpp/rclcpp.hpp"
+#include "nav2_costmap_2d/costmap_2d_ros.hpp"
+#include "tf2_ros/buffer.h"
+#include "nav_msgs/msg/path.hpp"
+#include "geometry_msgs/msg/pose_stamped.hpp"
+#include "nav2_util/lifecycle_node.hpp"
namespace nav2_core
{
@@ -32,6 +33,8 @@ namespace nav2_core
class GlobalPlanner
{
public:
+ using Ptr = std::shared_ptr<GlobalPlanner>;
+
/**
* @brief Virtual destructor
*/
@@ -43,8 +46,8 @@ public:
* @param tf A pointer to a TF buffer
* @param costmap_ros A pointer to the costmap
*/
- virtual void configure(const rclcpp::LifecycleNode * parent,
- const std::string & name, tf2_ros::Buffer * tf,
+ virtual void configure(rclcpp_lifecycle::LifecycleNode * parent,
+ std::string & name, tf2_ros::Buffer * tf,
nav2_costmap_2d::Costmap2DROS * costmap_ros) = 0;
/**
@@ -75,4 +78,4 @@ public:
} // namespace nav2_core
-#endif // NAV2_CORE_GLOBAL_PLANNER_H_
+#endif // NAV2_CORE__GLOBAL_PLANNER_H_
diff --git a/nav2_core/include/nav2_core/recovery.hpp b/nav2_core/include/nav2_core/recovery.hpp
index 1945b87d0299d6df5c07c21e5dc9b31ee9de6562..9c5a558c5fc66a443d4c74d319a18b1ad9ade08e 100644
--- a/nav2_core/include/nav2_core/recovery.hpp
+++ b/nav2_core/include/nav2_core/recovery.hpp
@@ -16,8 +16,9 @@
#define NAV2_CORE_RECOVERY_H_
#include <string>
-#include "rclcpp/rclcpp.h"
-#include "tf2_ros/Buffer.h"
+#include "rclcpp/rclcpp.hpp"
+#include "nav2_util/lifecycle_node.hpp"
+#include "tf2_ros/buffer.h"
namespace nav2_core
{
@@ -40,7 +41,7 @@ public:
* @param tf A pointer to a TF buffer
* @param costmap_ros A pointer to the costmap
*/
- virtual void configure(const rclcpp::LifecycleNode * parent,
+ virtual void configure(const nav2_util::LifecycleNode * parent,
const std::string & name, tf2_ros::Buffer * tf) = 0;
/**
diff --git a/nav2_core/package.xml b/nav2_core/package.xml
index a1f54f05177a6d5c2e7fc447d409453044b661ac..b86679ec1ed4502df80280cb93059a68b6967972 100644
--- a/nav2_core/package.xml
+++ b/nav2_core/package.xml
@@ -13,6 +13,8 @@
<depend>geometry_msgs</depend>
<depend>std_msgs</depend>
<depend>tf2_ros</depend>
+ <depend>nav2_utils</depend>
+ <depend>nav_msgs</depend>
<export>
<build_type>ament_cmake</build_type>