rclcpp_action
master
C++ ROS Action Client Library
|
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) |
using rclcpp_action::GoalUUID = typedef std::array<uint8_t, UUID_SIZE> |
using rclcpp_action::GoalStatus = typedef action_msgs::msg::GoalStatus |
using rclcpp_action::GoalInfo = typedef action_msgs::msg::GoalInfo |
|
strong |
|
strong |
A response returned by an action server callback when a goal is requested.
|
strong |
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
[in] | node_base_interface | The node base interface of the corresponding node. |
[in] | node_graph_interface | The node graph interface of the corresponding node. |
[in] | node_logging_interface | The node logging interface of the corresponding node. |
[in] | node_waitables_interface | The node waitables interface of the corresponding node. |
[in] | name | The action name. |
[in] | group | The action client will be added to this callback group. If nullptr , then the action client is added to the default callback group. |
[in] | options | Options to pass to the underlying rcl_action_client_t . |
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.
[in] | node | The action client will be added to this node. |
[in] | name | The action name. |
[in] | group | The action client will be added to this callback group. If nullptr , then the action client is added to the default callback group. |
[in] | options | Options to pass to the underlying rcl_action_client_t . |
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
[in] | node_base_interface | The node base interface of the corresponding node. |
[in] | node_clock_interface | The node clock interface of the corresponding node. |
[in] | node_logging_interface | The node logging interface of the corresponding node. |
[in] | node_waitables_interface | The node waitables interface of the corresponding node. |
[in] | name | The action name. |
[in] | handle_goal | A callback that decides if a goal should be accepted or rejected. |
[in] | handle_cancel | A 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_accepted | A callback that is called to give the user a handle to the goal. |
[in] | options | Options to pass to the underlying rcl_action_server_t . |
[in] | group | The action server will be added to this callback group. If nullptr , then the action server is added to the default callback group. |
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.
[in] | node] | The action server will be added to this node. |
[in] | name | The action name. |
[in] | handle_goal | A callback that decides if a goal should be accepted or rejected. |
[in] | handle_cancel | A 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_accepted | A callback that is called to give the user a handle to the goal. |
[in] | options | Options to pass to the underlying rcl_action_server_t . |
[in] | group | The action server will be added to this callback group. If nullptr , then the action server is added to the default callback group. |
RCLCPP_ACTION_PUBLIC std::string rclcpp_action::to_string | ( | const GoalUUID & | goal_id | ) |
Convert a goal id to a human readable string.
RCLCPP_ACTION_PUBLIC void rclcpp_action::convert | ( | const GoalUUID & | goal_id, |
rcl_action_goal_info_t * | info | ||
) |
RCLCPP_ACTION_PUBLIC void rclcpp_action::convert | ( | const rcl_action_goal_info_t & | info, |
GoalUUID * | goal_id | ||
) |