Skip to content

Commit

Permalink
async_cancel...() on client
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz committed Nov 16, 2018
1 parent a2b0cbe commit e79f5da
Showing 1 changed file with 9 additions and 0 deletions.
9 changes: 9 additions & 0 deletions rclcpp_action/include/rclcpp_action/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

#include <rosidl_generator_c/action_type_support_struct.h>
#include <rclcpp/node_interfaces/node_base_interface.hpp>
#include <rclcpp/time.hpp>
#include <rosidl_typesupport_cpp/action_type_support.hpp>

#include <functional>
Expand Down Expand Up @@ -82,6 +83,14 @@ class Client : public ClientBase
ClientGoalHandle<ACTION>
async_send_goal(typename ACTION::Goal * goal, FeedbackCallback callback = nullptr);

RCLCPP_ACTION_PUBLIC
std::future<typename ACTION::CancelGoalService::Response>
async_cancel_all_goals();

RCLCPP_ACTION_PUBLIC
std::future<typename ACTION::CancelGoalService::Response>
async_cancel_goals_before(rclcpp::Time);

virtual ~Client()
{
}
Expand Down

0 comments on commit e79f5da

Please sign in to comment.