diff --git a/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp b/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
index e1c3147a224fd052e724b5dce437581d73883272..fc8300c2cd156f6b4565f183f9244c46a454d78b 100644
--- a/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
+++ b/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
@@ -16,6 +16,7 @@
 
 #include <cmath>
 #include <memory>
+#include <string>
 
 #include "tf2_geometry_msgs/tf2_geometry_msgs.h"
 #include "nav2_util/geometry_utils.hpp"
diff --git a/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp b/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp
index 59f71cad2c2114a91069af8f1b501f01755764ab..1c960a21051539d5758b19833d4f3ad8c9134957 100644
--- a/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp
+++ b/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp
@@ -147,7 +147,8 @@ class InitialThread : public QThread
 public:
   using SystemStatus = nav2_lifecycle_manager::SystemStatus;
 
-  explicit InitialThread(nav2_lifecycle_manager::LifecycleManagerClient & client_nav,
+  explicit InitialThread(
+    nav2_lifecycle_manager::LifecycleManagerClient & client_nav,
     nav2_lifecycle_manager::LifecycleManagerClient & client_loc)
   : client_nav_(client_nav), client_loc_(client_loc)
   {}
diff --git a/nav2_rviz_plugins/src/nav2_panel.cpp b/nav2_rviz_plugins/src/nav2_panel.cpp
index a3ffb68a708e4d921f2c7b469c287c5d70a70c80..b1c91f67680e55af0dd850c66dbe14c77761cc38 100644
--- a/nav2_rviz_plugins/src/nav2_panel.cpp
+++ b/nav2_rviz_plugins/src/nav2_panel.cpp
@@ -263,18 +263,22 @@ void
 Nav2Panel::onPause()
 {
   QFuture<void> futureNav =
-    QtConcurrent::run(std::bind(&nav2_lifecycle_manager::LifecycleManagerClient::pause, &client_nav_));
+    QtConcurrent::run(std::bind(&nav2_lifecycle_manager::LifecycleManagerClient::pause,
+      &client_nav_));
   QFuture<void> futureLoc =
-    QtConcurrent::run(std::bind(&nav2_lifecycle_manager::LifecycleManagerClient::pause, &client_loc_));
+    QtConcurrent::run(std::bind(&nav2_lifecycle_manager::LifecycleManagerClient::pause,
+      &client_loc_));
 }
 
 void
 Nav2Panel::onResume()
 {
   QFuture<void> futureNav =
-    QtConcurrent::run(std::bind(&nav2_lifecycle_manager::LifecycleManagerClient::resume, &client_nav_));
+    QtConcurrent::run(std::bind(&nav2_lifecycle_manager::LifecycleManagerClient::resume,
+      &client_nav_));
   QFuture<void> futureLoc =
-    QtConcurrent::run(std::bind(&nav2_lifecycle_manager::LifecycleManagerClient::resume, &client_loc_));
+    QtConcurrent::run(std::bind(&nav2_lifecycle_manager::LifecycleManagerClient::resume,
+      &client_loc_));
 }
 
 void