AutoAPMS
Resilient Robot Mission Management
|
Convenience wrapper for a rclcpp_action::Client that introduces synchronous goal handling functions. More...
#include <auto_apms_util/action_client_wrapper.hpp>
Public Member Functions | |
ActionClientWrapper (rclcpp::Node::SharedPtr node_ptr, const std::string &action_name) | |
ActionClientWrapper constructor. | |
ResultFuture | syncSendGoal (const Goal &goal=Goal{}, const SendGoalOptions &options=SendGoalOptions{}, const std::chrono::seconds server_timeout=std::chrono::seconds{3}, const std::chrono::seconds response_timeout=std::chrono::seconds{3}) |
Send a goal to the action and synchronously wait for the response. | |
bool | syncCancelLastGoal (const std::chrono::seconds response_timeout=std::chrono::seconds{3}) |
Request to cancel the most recent goal. | |
ClientGoalHandle::SharedPtr | getActiveGoalHandle () |
Get the goal handle of the currently active goal. | |
std::shared_ptr< const Feedback > | getFeedback () |
Get the most recent feedback. | |
Static Public Member Functions | |
static ActionGoalStatus | getGoalStatus (const ResultFuture &future) |
Determine the status of a specific goal by evaluating the corresponding ActionClientWrapper::ResultFuture. | |
Convenience wrapper for a rclcpp_action::Client that introduces synchronous goal handling functions.
Definition at line 54 of file action_client_wrapper.hpp.
ActionClientWrapper | ( | rclcpp::Node::SharedPtr | node_ptr, |
const std::string & | action_name ) |
ActionClientWrapper constructor.
node_ptr | Shared pointer to the node. |
action_name | Name of the corresponding action. |
Definition at line 131 of file action_client_wrapper.hpp.
ActionClientWrapper< ActionT >::ResultFuture syncSendGoal | ( | const Goal & | goal = Goal{}, |
const SendGoalOptions & | options = SendGoalOptions{}, | ||
const std::chrono::seconds | server_timeout = std::chrono::seconds{3}, | ||
const std::chrono::seconds | response_timeout = std::chrono::seconds{3} ) |
Send a goal to the action and synchronously wait for the response.
goal | Goal of the action that will be sent to the server |
options | Goal options to be forwarded |
server_timeout | Timeout for waiting for the action server to be discovered |
response_timeout | Timeout for waiting for a goal response from the server |
nullptr
if the goal was rejected. std::runtime_error | if sending the goal fails. |
Definition at line 140 of file action_client_wrapper.hpp.
bool syncCancelLastGoal | ( | const std::chrono::seconds | response_timeout = std::chrono::seconds{3} | ) |
Request to cancel the most recent goal.
This method is synchronous, meaning that it blocks until the cancelation result is received.
response_timeout | Timeout for waiting for a cancel response from the server |
true
if the last goal was cancelled successfully, false
if request was denied. std::runtime_error | if cancelation failed. |
Definition at line 190 of file action_client_wrapper.hpp.
|
static |
Determine the status of a specific goal by evaluating the corresponding ActionClientWrapper::ResultFuture.
future | ActionClientWrapper::ResultFuture corresponding to the goal whose status is to be retrieved |
std::runtime_error | if future is invalid. |
Definition at line 224 of file action_client_wrapper.hpp.
ActionClientWrapper< ActionT >::ClientGoalHandle::SharedPtr getActiveGoalHandle | ( | ) |
Get the goal handle of the currently active goal.
nullptr
, if there is no active goal. Definition at line 239 of file action_client_wrapper.hpp.
std::shared_ptr< const typename ActionClientWrapper< ActionT >::Feedback > getFeedback | ( | ) |
Get the most recent feedback.
Definition at line 245 of file action_client_wrapper.hpp.