diff --git a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp
index a96060b0ad251be8fc4f06ae80690ea161a0a7b7..c54a8dd07ba4ce2096de0f6e54d47023d03fed7a 100644
--- a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp
+++ b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp
@@ -31,11 +31,20 @@ namespace nav2_lifecycle_manager
 {
 
 using nav2_msgs::srv::ManageLifecycleNodes;
-
+/**
+ * @class nav2_lifecycle_manager::LifecycleManager
+ * @brief Implements lifecycle node manager service
+ */
 class LifecycleManager : public rclcpp::Node
 {
 public:
+  /**
+   * @brief A constructor for nav2_lifecycle_manager::LifecycleManager
+   */
   LifecycleManager();
+  /**
+   * @brief A destructor for nav2_lifecycle_manager::LifecycleManager
+   */
   ~LifecycleManager();
 
 protected:
@@ -45,38 +54,84 @@ protected:
   // The services provided by this node
   rclcpp::Service<ManageLifecycleNodes>::SharedPtr manager_srv_;
   rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr is_active_srv_;
-
+  /**
+   * @brief Lifecycle node manager callback function
+   * @param request_header Header of the service request
+   * @param request Service request
+   * @param reponse Service response
+   */
   void managerCallback(
     const std::shared_ptr<rmw_request_id_t> request_header,
     const std::shared_ptr<ManageLifecycleNodes::Request> request,
     std::shared_ptr<ManageLifecycleNodes::Response> response);
-
+  /**
+   * @brief Trigger callback funcition checks if the system is active or not
+   * @param request_header Header of the request
+   * @param request Service request
+   * @param reponse Service response
+   */
   void isActiveCallback(
     const std::shared_ptr<rmw_request_id_t> request_header,
     const std::shared_ptr<std_srvs::srv::Trigger::Request> request,
     std::shared_ptr<std_srvs::srv::Trigger::Response> response);
 
   // Support functions for the service calls
+  /**
+   * @brief Start up manage nodes.
+   * @return true or false
+   */
   bool startup();
+  /**
+   * @brief Deactivates, clean up and shutdown all the manage nodes.
+   * @return true or false
+   */
   bool shutdown();
+  /**
+   * @brief Reset all the manage nodes.
+   * @return true or false
+   */
   bool reset();
+  /**
+   * @brief Pause all the manage nodes.
+   * @return true or false
+   */
   bool pause();
+  /**
+   * @brief Resume all the manage nodes.
+   * @return true or false
+   */
   bool resume();
 
   // Support function for creating service clients
+  /**
+   * @brief Support function for creating service clients
+   */
   void createLifecycleServiceClients();
 
   // Support functions for shutdown
+  /**
+   * @brief Support function for shutdown
+   */
   void shutdownAllNodes();
+  /**
+   * @brief Destroy all the lifecycle service clients.
+   */
   void destroyLifecycleServiceClients();
 
-  // For a node, transition to the new target state
+  /**
+   * @brief For a node, transition to the new target state
+   */
   bool changeStateForNode(const std::string & node_name, std::uint8_t transition);
 
-  // For each node in the map, transition to the new target state
+  /**
+   * @brief For each node in the map, transition to the new target state
+   */
   bool changeStateForAllNodes(std::uint8_t transition, bool reverse_order = false);
 
   // Convenience function to highlight the output on the console
+  /**
+   * @brief Helper function to highlight the output on the console
+   */
   void message(const std::string & msg);
 
   // A map of all nodes to be controlled
diff --git a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp
index dbe76cf5deb80eac8325d224b459498ca5cd24ef..2be5e4777a10259505863ddf09b7be912b034dae 100644
--- a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp
+++ b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp
@@ -29,30 +29,80 @@
 
 namespace nav2_lifecycle_manager
 {
-
+/**
+ * @enum nav2_lifecycle_manager::SystemStatus
+ * @brief Enum class representing the status of the system.
+ */
 enum class SystemStatus {ACTIVE, INACTIVE, TIMEOUT};
-
+/**
+ * @class nav2_lifecycle_manager::LifeCycleMangerClient
+ * @brief Implements lifecycle manager service client and NavigateToPose action
+ * client
+ */
 class LifecycleManagerClient
 {
 public:
+  /**
+   * @brief A constructor for LifeCycleMangerClient
+   */
   LifecycleManagerClient();
 
   // Client-side interface to the Nav2 lifecycle manager
+  /**
+   * @brief Makes start up service call
+   * @return true or false
+   */
   bool startup();
+  /**
+   * @brief Makes shutdown service call
+   * @return true or false
+   */
   bool shutdown();
+  /**
+   * @brief Makes pause service call
+   * @return true or false
+   */
   bool pause();
+  /**
+   * @brief Makes resume service call
+   * @return true or false
+   */
   bool resume();
+  /**
+   * @brief Makes reset service call
+   * @return true or false
+   */
   bool reset();
+  /**
+   * @brief Checks if lifecycle node manager server is active
+   * @return ACTIVE or INACTIVE or TIMEOUT
+   */
   SystemStatus is_active(const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
 
   // A couple convenience methods to facilitate scripting tests
+  /**
+   * @brief Sets initial pose with covariance
+   * @param x X position
+   * @param y Y position
+   * @param theta orientation
+   */
   void set_initial_pose(double x, double y, double theta);
+  /**
+   * @brief Sends goal pose to NavigationToPose action server
+   * @param x X position
+   * @param y Y position
+   * @param theta orientation
+   * @return true or false
+   */
   bool navigate_to_pose(double x, double y, double theta);
 
 protected:
   using ManageLifecycleNodes = nav2_msgs::srv::ManageLifecycleNodes;
 
-  // A generic method used to call startup, shutdown, etc.
+  /**
+   * @brief A generic method used to call startup, shutdown, etc.
+   * @param command
+   */
   bool callService(uint8_t command);
 
   // The node to use for the service call