AutoAPMS
Resilient Robot Mission Management
|
#include <auto_apms_core/action_client.hpp>
Public Types | |
using | Goal = typename ActionT::Goal |
using | SendGoalOptions = typename rclcpp_action::Client<ActionT>::SendGoalOptions |
using | Feedback = typename ActionT::Feedback |
using | Result = typename ActionT::Result |
using | ClientGoalHandle = rclcpp_action::ClientGoalHandle<ActionT> |
using | WrappedResultSharedPtr = std::shared_ptr<typename ClientGoalHandle::WrappedResult> |
using | ResultFuture = std::shared_future<WrappedResultSharedPtr> |
Public Member Functions | |
ActionClientWrapper (rclcpp::Node &node, const std::string &action_name) | |
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 }) |
bool | syncCancelLastGoal (const std::chrono::seconds response_timeout=std::chrono::seconds{ 3 }) |
ClientGoalHandle::SharedPtr | getActiveGoalHandle () |
std::shared_ptr< const Feedback > | getFeedback () |
Static Public Member Functions | |
static ActionGoalStatus | getGoalStatus (const ResultFuture &future) |
Convenience wrapper for a rclcpp_action::Client that introduces synchronous goal handling functions.
Definition at line 45 of file action_client.hpp.
using Goal = typename ActionT::Goal |
Definition at line 48 of file action_client.hpp.
using SendGoalOptions = typename rclcpp_action::Client<ActionT>::SendGoalOptions |
Definition at line 49 of file action_client.hpp.
using Feedback = typename ActionT::Feedback |
Definition at line 50 of file action_client.hpp.
using Result = typename ActionT::Result |
Definition at line 51 of file action_client.hpp.
using ClientGoalHandle = rclcpp_action::ClientGoalHandle<ActionT> |
Definition at line 52 of file action_client.hpp.
using WrappedResultSharedPtr = std::shared_ptr<typename ClientGoalHandle::WrappedResult> |
Definition at line 53 of file action_client.hpp.
using ResultFuture = std::shared_future<WrappedResultSharedPtr> |
Definition at line 54 of file action_client.hpp.
ActionClientWrapper | ( | rclcpp::Node & | node, |
const std::string & | action_name ) |
Constructor.
node | Node reference. This instance doesn't own the node |
action_name | Name of the corresponding action |
Definition at line 121 of file action_client.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 131 of file action_client.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 186 of file action_client.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 223 of file action_client.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 241 of file action_client.hpp.
std::shared_ptr< const typename ActionClientWrapper< ActionT >::Feedback > getFeedback | ( | ) |
Get the most recent feedback.
Definition at line 247 of file action_client.hpp.