rclcpp_action
master
C++ ROS Action Client Library
|
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) |
using rclcpp_action::GoalID = 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::SharedPtr | node, |
const std::string & | name, | ||
rclcpp::callback_group::CallbackGroup::SharedPtr | group = nullptr |
||
) |
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 |
||
) |
RCLCPP_ACTION_PUBLIC std::string rclcpp_action::to_string | ( | const GoalID & | goal_id | ) |
Convert a goal id to a human readable string.
RCLCPP_ACTION_PUBLIC void rclcpp_action::convert | ( | const GoalID & | goal_id, |
rcl_action_goal_info_t * | info | ||
) |
RCLCPP_ACTION_PUBLIC void rclcpp_action::convert | ( | const rcl_action_goal_info_t & | info, |
GoalID * | goal_id | ||
) |