rclcpp_action  master
C++ ROS Action Client Library
Namespaces | Classes | Typedefs | Enumerations | Functions
rclcpp_action Namespace Reference

Namespaces

 exceptions
 

Classes

class  Client
 Action Client. More...
 
class  ClientBase
 
class  ClientGoalHandle
 Class for interacting with goals sent from action clients. More...
 
class  DefaultActionStatusQoS
 
class  Server
 Action Server. More...
 
class  ServerBase
 
class  ServerGoalHandle
 Class to interact with goals on a server. More...
 
class  ServerGoalHandleBase
 

Typedefs

using GoalUUID = std::array< uint8_t, UUID_SIZE >
 
using GoalStatus = action_msgs::msg::GoalStatus
 
using GoalInfo = action_msgs::msg::GoalInfo
 

Enumerations

enum  ResultCode : int8_t { ResultCode::UNKNOWN = action_msgs::msg::GoalStatus::STATUS_UNKNOWN, ResultCode::SUCCEEDED = action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, ResultCode::CANCELED = action_msgs::msg::GoalStatus::STATUS_CANCELED, ResultCode::ABORTED = action_msgs::msg::GoalStatus::STATUS_ABORTED }
 The possible statuses that an action goal can finish with. More...
 
enum  GoalResponse : int8_t { GoalResponse::REJECT = 1, GoalResponse::ACCEPT_AND_EXECUTE = 2, GoalResponse::ACCEPT_AND_DEFER = 3 }
 A response returned by an action server callback when a goal is requested. More...
 
enum  CancelResponse : int8_t { CancelResponse::REJECT = 1, CancelResponse::ACCEPT = 2 }
 A response returned by an action server callback when a goal has been asked to be canceled. More...
 

Functions

template<typename ActionT >
Client< ActionT >::SharedPtr create_client (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, const std::string &name, rclcpp::CallbackGroup::SharedPtr group=nullptr, const rcl_action_client_options_t &options=rcl_action_client_get_default_options())
 Create an action client. More...
 
template<typename ActionT , typename NodeT >
Client< ActionT >::SharedPtr create_client (NodeT node, const std::string &name, rclcpp::CallbackGroup::SharedPtr group=nullptr, const rcl_action_client_options_t &options=rcl_action_client_get_default_options())
 Create an action client. More...
 
template<typename ActionT >
Server< ActionT >::SharedPtr create_server (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, const std::string &name, typename Server< ActionT >::GoalCallback handle_goal, typename Server< ActionT >::CancelCallback handle_cancel, typename Server< ActionT >::AcceptedCallback handle_accepted, const rcl_action_server_options_t &options=rcl_action_server_get_default_options(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
 Create an action server. More...
 
template<typename ActionT , typename NodeT >
Server< ActionT >::SharedPtr create_server (NodeT node, const std::string &name, typename Server< ActionT >::GoalCallback handle_goal, typename Server< ActionT >::CancelCallback handle_cancel, typename Server< ActionT >::AcceptedCallback handle_accepted, const rcl_action_server_options_t &options=rcl_action_server_get_default_options(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
 Create an action server. More...
 
RCLCPP_ACTION_PUBLIC std::string to_string (const GoalUUID &goal_id)
 Convert a goal id to a human readable string. More...
 
RCLCPP_ACTION_PUBLIC void convert (const GoalUUID &goal_id, rcl_action_goal_info_t *info)
 
RCLCPP_ACTION_PUBLIC void convert (const rcl_action_goal_info_t &info, GoalUUID *goal_id)
 

Typedef Documentation

◆ GoalUUID

using rclcpp_action::GoalUUID = typedef std::array<uint8_t, UUID_SIZE>

◆ GoalStatus

using rclcpp_action::GoalStatus = typedef action_msgs::msg::GoalStatus

◆ GoalInfo

using rclcpp_action::GoalInfo = typedef action_msgs::msg::GoalInfo

Enumeration Type Documentation

◆ ResultCode

enum rclcpp_action::ResultCode : int8_t
strong

The possible statuses that an action goal can finish with.

Enumerator
UNKNOWN 
SUCCEEDED 
CANCELED 
ABORTED 

◆ GoalResponse

enum rclcpp_action::GoalResponse : int8_t
strong

A response returned by an action server callback when a goal is requested.

Enumerator
REJECT 

The goal is rejected and will not be executed.

ACCEPT_AND_EXECUTE 

The server accepts the goal, and is going to begin execution immediately.

ACCEPT_AND_DEFER 

The server accepts the goal, and is going to execute it later.

◆ CancelResponse

enum rclcpp_action::CancelResponse : int8_t
strong

A response returned by an action server callback when a goal has been asked to be canceled.

Enumerator
REJECT 

The server will not try to cancel the goal.

ACCEPT 

The server has agreed to try to cancel the goal.

Function Documentation

◆ create_client() [1/2]

template<typename ActionT >
Client<ActionT>::SharedPtr rclcpp_action::create_client ( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node_base_interface,
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr  node_graph_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr  node_logging_interface,
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr  node_waitables_interface,
const std::string name,
rclcpp::CallbackGroup::SharedPtr  group = nullptr,
const rcl_action_client_options_t options = rcl_action_client_get_default_options() 
)

Create an action client.

This function is equivalent to

See also
create_client()` however is using the individual node interfaces to create the client.
Parameters
[in]node_base_interfaceThe node base interface of the corresponding node.
[in]node_graph_interfaceThe node graph interface of the corresponding node.
[in]node_logging_interfaceThe node logging interface of the corresponding node.
[in]node_waitables_interfaceThe node waitables interface of the corresponding node.
[in]nameThe action name.
[in]groupThe action client will be added to this callback group. If nullptr, then the action client is added to the default callback group.
[in]optionsOptions to pass to the underlying rcl_action_client_t.

◆ create_client() [2/2]

template<typename ActionT , typename NodeT >
Client<ActionT>::SharedPtr rclcpp_action::create_client ( NodeT  node,
const std::string name,
rclcpp::CallbackGroup::SharedPtr  group = nullptr,
const rcl_action_client_options_t options = rcl_action_client_get_default_options() 
)

Create an action client.

Parameters
[in]nodeThe action client will be added to this node.
[in]nameThe action name.
[in]groupThe action client will be added to this callback group. If nullptr, then the action client is added to the default callback group.
[in]optionsOptions to pass to the underlying rcl_action_client_t.

◆ create_server() [1/2]

template<typename ActionT >
Server<ActionT>::SharedPtr rclcpp_action::create_server ( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node_base_interface,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr  node_clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr  node_logging_interface,
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr  node_waitables_interface,
const std::string name,
typename Server< ActionT >::GoalCallback  handle_goal,
typename Server< ActionT >::CancelCallback  handle_cancel,
typename Server< ActionT >::AcceptedCallback  handle_accepted,
const rcl_action_server_options_t options = rcl_action_server_get_default_options(),
rclcpp::CallbackGroup::SharedPtr  group = nullptr 
)

Create an action server.

All provided callback functions must be non-blocking. This function is equivalent to

See also
create_server()` however is using the individual node interfaces to create the server.
Server::Server() for more information.
Parameters
[in]node_base_interfaceThe node base interface of the corresponding node.
[in]node_clock_interfaceThe node clock interface of the corresponding node.
[in]node_logging_interfaceThe node logging interface of the corresponding node.
[in]node_waitables_interfaceThe node waitables interface of the corresponding node.
[in]nameThe action name.
[in]handle_goalA callback that decides if a goal should be accepted or rejected.
[in]handle_cancelA callback that decides if a goal should be attempted to be canceled. The return from this callback only indicates if the server will try to cancel a goal. It does not indicate if the goal was actually canceled.
[in]handle_acceptedA callback that is called to give the user a handle to the goal.
[in]optionsOptions to pass to the underlying rcl_action_server_t.
[in]groupThe action server will be added to this callback group. If nullptr, then the action server is added to the default callback group.

◆ create_server() [2/2]

template<typename ActionT , typename NodeT >
Server<ActionT>::SharedPtr rclcpp_action::create_server ( NodeT  node,
const std::string name,
typename Server< ActionT >::GoalCallback  handle_goal,
typename Server< ActionT >::CancelCallback  handle_cancel,
typename Server< ActionT >::AcceptedCallback  handle_accepted,
const rcl_action_server_options_t options = rcl_action_server_get_default_options(),
rclcpp::CallbackGroup::SharedPtr  group = nullptr 
)

Create an action server.

All provided callback functions must be non-blocking.

See also
Server::Server() for more information.
Parameters
[in]node]The action server will be added to this node.
[in]nameThe action name.
[in]handle_goalA callback that decides if a goal should be accepted or rejected.
[in]handle_cancelA callback that decides if a goal should be attempted to be canceled. The return from this callback only indicates if the server will try to cancel a goal. It does not indicate if the goal was actually canceled.
[in]handle_acceptedA callback that is called to give the user a handle to the goal.
[in]optionsOptions to pass to the underlying rcl_action_server_t.
[in]groupThe action server will be added to this callback group. If nullptr, then the action server is added to the default callback group.

◆ to_string()

RCLCPP_ACTION_PUBLIC std::string rclcpp_action::to_string ( const GoalUUID goal_id)

Convert a goal id to a human readable string.

◆ convert() [1/2]

RCLCPP_ACTION_PUBLIC void rclcpp_action::convert ( const GoalUUID goal_id,
rcl_action_goal_info_t *  info 
)

◆ convert() [2/2]

RCLCPP_ACTION_PUBLIC void rclcpp_action::convert ( const rcl_action_goal_info_t &  info,
GoalUUID goal_id 
)