Template Class ActionClientWrapper
Defined in File action_client_wrapper.hpp
Class Documentation
-
template<typename ActionT>
class ActionClientWrapper Convenience wrapper for a rclcpp_action::Client that introduces synchronous goal handling functions.
Public Functions
ActionClientWrapper constructor.
- Parameters:
node_ptr – Shared pointer to the node.
action_name – Name of the corresponding action.
-
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.
- Parameters:
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
- Throws:
std::runtime_error – if sending the goal fails.
- Returns:
Shared future that completes when the action finishes, holding the result. The result is
nullptrif the goal was rejected.
-
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.
- Parameters:
response_timeout – Timeout for waiting for a cancel response from the server
- Throws:
std::runtime_error – if cancelation failed.
- Returns:
trueif the last goal was cancelled successfully,falseif request was denied.
-
ClientGoalHandle::SharedPtr getActiveGoalHandle()
Get the goal handle of the currently active goal.
- Returns:
Shared pointer of the active goal handle or
nullptr, if there is no active goal.
Public Static Functions
-
static ActionGoalStatus getGoalStatus(const ResultFuture &future)
Determine the status of a specific goal by evaluating the corresponding ActionClientWrapper::ResultFuture.
- Parameters:
future – ActionClientWrapper::ResultFuture corresponding to the goal whose status is to be retrieved
- Throws:
std::runtime_error – if
futureis invalid.- Returns:
auto_apms::ActionGoalStatus value that indicates whether the goal was rejected, is currently being processed or has completed.