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  Server
 Action Server. More...
 
class  ServerBase
 
class  ServerGoalHandle
 Class to interact with goals on a server. More...
 
class  ServerGoalHandleBase
 

Typedefs

using GoalID = 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::SharedPtr node, const std::string &name, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
 
template<typename ActionT >
Server< ActionT >::SharedPtr create_server (rclcpp::Node::SharedPtr 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::callback_group::CallbackGroup::SharedPtr group=nullptr)
 
RCLCPP_ACTION_PUBLIC std::string to_string (const GoalID &goal_id)
 Convert a goal id to a human readable string. More...
 
RCLCPP_ACTION_PUBLIC void convert (const GoalID &goal_id, rcl_action_goal_info_t *info)
 
RCLCPP_ACTION_PUBLIC void convert (const rcl_action_goal_info_t &info, GoalID *goal_id)
 

Typedef Documentation

◆ GoalID

using rclcpp_action::GoalID = 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()

template<typename ActionT >
Client<ActionT>::SharedPtr rclcpp_action::create_client ( rclcpp::Node::SharedPtr  node,
const std::string name,
rclcpp::callback_group::CallbackGroup::SharedPtr  group = nullptr 
)

◆ create_server()

template<typename ActionT >
Server<ActionT>::SharedPtr rclcpp_action::create_server ( rclcpp::Node::SharedPtr  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::callback_group::CallbackGroup::SharedPtr  group = nullptr 
)

◆ to_string()

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

Convert a goal id to a human readable string.

◆ convert() [1/2]

RCLCPP_ACTION_PUBLIC void rclcpp_action::convert ( const GoalID 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,
GoalID goal_id 
)