Template Class ServerGoalHandle

Inheritance Relationships

Base Type

Class Documentation

template<typename ActionT>
class ServerGoalHandle : public rclcpp_action::ServerGoalHandleBase

Class to interact with goals on a server.

Use this class to check the status of a goal as well as set the result.

This class is not meant to be created by a user, instead it is created when a goal has been accepted. A Server will create an instance and give it to the user in their handle_accepted callback.

Internally, this class is responsible for coverting between the C++ action type and generic types for rclcpp_action::ServerGoalHandleBase.

Public Functions

inline void publish_feedback(std::shared_ptr<typename ActionT::Feedback> feedback_msg)

Send an update about the progress of a goal.

This must only be called when the goal is executing. If execution of a goal is deferred then ServerGoalHandle::set_executing() must be called first.

Throws:

std::runtime_error – If the goal is in any state besides executing.

Parameters:

feedback_msg[in] the message to publish to clients.

inline void abort(typename ActionT::Result::SharedPtr result_msg)

Indicate that a goal could not be reached and has been aborted.

Only call this if the goal was executing but cannot be completed. This is a terminal state, no more methods should be called on a goal handle after this is called.

Throws:

rclcpp::exceptions::RCLError – If the goal is in any state besides executing.

Parameters:

result_msg[in] the final result to send to clients.

inline void succeed(typename ActionT::Result::SharedPtr result_msg)

Indicate that a goal has succeeded.

Only call this if the goal is executing and has reached the desired final state. This is a terminal state, no more methods should be called on a goal handle after this is called.

Throws:

rclcpp::exceptions::RCLError – If the goal is in any state besides executing.

Parameters:

result_msg[in] the final result to send to clients.

inline void canceled(typename ActionT::Result::SharedPtr result_msg)

Indicate that a goal has been canceled.

Only call this if the goal is executing or pending, but has been canceled. This is a terminal state, no more methods should be called on a goal handle after this is called.

Throws:

rclcpp::exceptions::RCLError – If the goal is in any state besides executing.

Parameters:

result_msg[in] the final result to send to clients.

inline void execute()

Indicate that the server is starting to execute a goal.

Only call this if the goal is pending.

Throws:

rclcpp::exceptions::RCLError – If the goal is in any state besides executing.

inline const std::shared_ptr<const typename ActionT::Goal> get_goal() const

Get the user provided message describing the goal.

inline const GoalUUID &get_goal_id() const

Get the unique identifier of the goal.

inline virtual ~ServerGoalHandle()

Protected Functions

inline ServerGoalHandle(std::shared_ptr<rcl_action_goal_handle_t> rcl_handle, GoalUUID uuid, std::shared_ptr<const typename ActionT::Goal> goal, std::function<void(const GoalUUID&, std::shared_ptr<void>)> on_terminal_state, std::function<void(const GoalUUID&)> on_executing, std::function<void(std::shared_ptr<typename ActionT::Impl::FeedbackMessage>)> publish_feedback)

Protected Attributes

const std::shared_ptr<const typename ActionT::Goal> goal_

The user provided message describing the goal.

const GoalUUID uuid_

A unique id for the goal request.

std::function<void(const GoalUUID&, std::shared_ptr<void>)> on_terminal_state_
std::function<void(const GoalUUID&)> on_executing_
std::function<void(std::shared_ptr<typename ActionT::Impl::FeedbackMessage>)> publish_feedback_

Friends

friend class Server< ActionT >