diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp
index 15247339230b448de3d48dd3db67d4828a5fc618..fd6a4cb25793ccf43d0c261909dc83dcc522b6c6 100644
--- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp
+++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp
@@ -104,12 +104,8 @@ public:
   {
     on_tick();
 
-    // Enable result awareness by providing an empty lambda function
-    auto send_goal_options = typename rclcpp_action::Client<ActionT>::SendGoalOptions();
-    send_goal_options.result_callback = [](auto) {};
-
 new_goal_received:
-    auto future_goal_handle = action_client_->async_send_goal(goal_, send_goal_options);
+    auto future_goal_handle = action_client_->async_send_goal(goal_);
     if (rclcpp::spin_until_future_complete(node_, future_goal_handle) !=
       rclcpp::executor::FutureReturnCode::SUCCESS)
     {
@@ -121,7 +117,7 @@ new_goal_received:
       throw std::runtime_error("Goal was rejected by the action server");
     }
 
-    auto future_result = goal_handle_->async_result();
+    auto future_result = action_client_->async_get_result(goal_handle_);
     rclcpp::executor::FutureReturnCode rc;
     do {
       rc = rclcpp::spin_until_future_complete(node_, future_result, server_timeout_);
diff --git a/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp b/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
index 05c081c5101e5617c6ab951a6bff94d965d57c23..747782b7c73ece04e264fcf78940fde112ddc9b5 100644
--- a/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
+++ b/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp
@@ -134,13 +134,8 @@ LifecycleManagerClient::navigate_to_pose(double x, double y, double theta)
   auto goal = nav2_msgs::action::NavigateToPose::Goal();
   goal.pose = target_pose;
 
-  // Enable result awareness by providing an empty lambda function
-  auto send_goal_options =
-    typename rclcpp_action::Client<nav2_msgs::action::NavigateToPose>::SendGoalOptions();
-  send_goal_options.result_callback = [](auto) {};
-
   // Send it
-  auto future_goal_handle = navigate_action_client_->async_send_goal(goal, send_goal_options);
+  auto future_goal_handle = navigate_action_client_->async_send_goal(goal);
   if (rclcpp::spin_until_future_complete(node_, future_goal_handle) !=
     rclcpp::executor::FutureReturnCode::SUCCESS)
   {
@@ -156,7 +151,8 @@ LifecycleManagerClient::navigate_to_pose(double x, double y, double theta)
   }
 
   // Wait for the action to complete
-  auto future_result = goal_handle->async_result();
+  auto future_result = navigate_action_client_->async_get_result(goal_handle);
+
   if (rclcpp::spin_until_future_complete(node_, future_result) !=
     rclcpp::executor::FutureReturnCode::SUCCESS)
   {
diff --git a/nav2_recoveries/test/test_recoveries.cpp b/nav2_recoveries/test/test_recoveries.cpp
index c7e70fce95511ebd96c61034314a49bfef557e7d..84a716cfd15f966562d5c224290bc2aa6be0cf7d 100644
--- a/nav2_recoveries/test/test_recoveries.cpp
+++ b/nav2_recoveries/test/test_recoveries.cpp
@@ -162,11 +162,7 @@ protected:
   {
     auto goal = RecoveryAction::Goal();
     goal.command.data = command;
-
-    auto goal_options = rclcpp_action::Client<RecoveryAction>::SendGoalOptions();
-    goal_options.result_callback = [](auto) {};
-
-    return client_->async_send_goal(goal, goal_options);
+    return client_->async_send_goal(goal);
   }
 
   Status getOutcome()
@@ -180,7 +176,7 @@ protected:
 
   ClientGoalHandle::WrappedResult getResult()
   {
-    auto future_result = goal_handle_->async_result();
+    auto future_result = client_->async_get_result(goal_handle_);
     rclcpp::executor::FutureReturnCode frc;
 
     do {