Skip to content

Commit

Permalink
Use action client get result method
Browse files Browse the repository at this point in the history
Since a result callback is not provided when sending the goal, the goal handle is not "result aware"
and calling the action client method will make it so.

The behaviour was changed in ros2/rclcpp#701.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed May 24, 2019
1 parent 1129fe8 commit c52bdcf
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion rclcpp/minimal_action_client/not_composable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ int main(int argc, char ** argv)
}

// Wait for the server to be done with the goal
auto result_future = goal_handle->async_result();
auto result_future = action_client->async_get_result(goal_handle);

RCLCPP_INFO(node->get_logger(), "Waiting for result");
if (rclcpp::spin_until_future_complete(node, result_future) !=
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ int main(int argc, char ** argv)
}

// Wait for the server to be done with the goal
auto result_future = goal_handle->async_result();
auto result_future = action_client->async_get_result(goal_handle);

auto wait_result = rclcpp::spin_until_future_complete(
node,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ int main(int argc, char ** argv)
}

// Wait for the server to be done with the goal
auto result_future = goal_handle->async_result();
auto result_future = action_client->async_get_result(goal_handle);

RCLCPP_INFO(g_node->get_logger(), "Waiting for result");
if (rclcpp::spin_until_future_complete(g_node, result_future) !=
Expand Down

0 comments on commit c52bdcf

Please sign in to comment.