Skip to content

Commit

Permalink
Add documentation to rclcpp_action
Browse files Browse the repository at this point in the history
Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron authored and christopherho-ApexAI committed Jun 3, 2019
1 parent efdd09b commit 569c228
Show file tree
Hide file tree
Showing 7 changed files with 128 additions and 14 deletions.
59 changes: 58 additions & 1 deletion rclcpp_action/include/rclcpp_action/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -245,7 +245,7 @@ class ClientBase : public rclcpp::Waitable
/**
* This class creates an action client.
*
* Create an instance of this server using `rclcpp_action::create_client()`.
* To create an instance of an action client use `rclcpp_action::create_client()`.
*
* Internally, this class is responsible for:
* - coverting between the C++ action type and generic types for `rclcpp_action::ClientBase`, and
Expand All @@ -265,6 +265,18 @@ class Client : public ClientBase
using CancelRequest = typename ActionT::Impl::CancelGoalService::Request;
using CancelResponse = typename ActionT::Impl::CancelGoalService::Response;

/// Construct an action client.
/**
* This constructs an action client, but it will not work until it has been added to a node.
* Use `rclcpp_action::create_client()` to both construct and add to a node.
*
* \param[in] node_base A pointer to the base interface of a node.
* \param[in] node_graph A pointer to an interface that allows getting graph information about
* a node.
* \param[in] node_logging A pointer to an interface that allows getting a node's logger.
* \param[in] action_name The action name.
* \param[in] client_options Options to pass to the underlying `rcl_action::rcl_action_client_t`.
*/
Client(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
Expand All @@ -279,6 +291,20 @@ class Client : public ClientBase
{
}

/// Send an action goal and asynchronously get the result.
/**
* If the goal is accepted by an action server, the returned future is set to a `ClientGoalHandle`.
* If the goal is rejected by an action server, then the future is set to a `nullptr`.
*
* The goal handle is used to monitor the status of the goal and get the final result.
*
* \param[in] goal The goal request.
* \param[in] callback Optional user callback for feedback associated with the goal.
* \param[in] ignore_result If `true`, then the result for the goal will not be requested and
* therefore inaccessible from the goal handle.
* \return A future that completes when the goal has been accepted or rejected.
* If the goal is rejected, then the result will be a `nullptr`.
*/
std::shared_future<typename GoalHandle::SharedPtr>
async_send_goal(
const Goal & goal, FeedbackCallback callback = nullptr, bool ignore_result = false)
Expand Down Expand Up @@ -321,6 +347,13 @@ class Client : public ClientBase
return future;
}

/// Asynchronously get the result for an active goal.
/**
* \throws exceptions::UnknownGoalHandleError If the goal unknown or already reached a terminal
* state.
* \param[in] goal_handle The goal handle for which to get the result.
* \return A future that is set to the goal result when the goal is finished.
*/
std::shared_future<WrappedResult>
async_get_result(typename GoalHandle::SharedPtr goal_handle)
{
Expand All @@ -335,6 +368,13 @@ class Client : public ClientBase
return goal_handle->async_result();
}

/// Asynchronously request a goal be canceled.
/**
* \throws exceptions::UnknownGoalHandleError If the goal is unknown or already reached a
* terminal state.
* \param[in] goal_handle The goal handle requesting to be canceled.
* \return A future whose result indicates whether or not the cancel request was accepted.
*/
std::shared_future<bool>
async_cancel_goal(typename GoalHandle::SharedPtr goal_handle)
{
Expand Down Expand Up @@ -364,6 +404,14 @@ class Client : public ClientBase
return future;
}

/// Asynchronously request for all goals to be canceled.
/**
* \return A future to a CancelResponse message that is set when the request has been
* acknowledged by an action server.
* See
* <a href="https://github.com/ros2/rcl_interfaces/blob/master/action_msgs/srv/CancelGoal.srv">
* action_msgs/CancelGoal.srv</a>.
*/
std::shared_future<typename CancelResponse::SharedPtr>
async_cancel_all_goals()
{
Expand All @@ -375,6 +423,15 @@ class Client : public ClientBase
return async_cancel(cancel_request);
}

/// Asynchronously request all goals at or before a specified time be canceled.
/**
* \param[in] stamp The timestamp for the cancel goal request.
* \return A future to a CancelResponse message that is set when the request has been
* acknowledged by an action server.
* See
* <a href="https://github.com/ros2/rcl_interfaces/blob/master/action_msgs/srv/CancelGoal.srv">
* action_msgs/CancelGoal.srv</a>.
*/
std::shared_future<typename CancelResponse::SharedPtr>
async_cancel_goals_before(const rclcpp::Time & stamp)
{
Expand Down
24 changes: 24 additions & 0 deletions rclcpp_action/include/rclcpp_action/client_goal_handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,15 @@ enum class ResultCode : int8_t
template<typename ActionT>
class Client;

/// Class for interacting with goals sent from action clients.
/**
* Use this class to check the status of a goal as well as get the result.
*
* This class is not meant to be created by a user, instead it is created when a goal has been
* accepted.
* A `Client` will create an instance and return it to the user (via a future) after calling
* `Client::async_send_goal`.
*/
template<typename ActionT>
class ClientGoalHandle
{
Expand All @@ -70,21 +79,36 @@ class ClientGoalHandle

virtual ~ClientGoalHandle();

/// Get the unique ID for the goal.
const GoalUUID &
get_goal_id() const;

/// Get the time when the goal was accepted.
rclcpp::Time
get_goal_stamp() const;

/// Get a future to the goal result.
/**
* This method should not be called if the `ignore_result` flag was set when
* sending the original goal request (see Client::async_send_goal).
*
* `is_result_aware()` can be used to check if it is safe to call this method.
*
* \throws exceptions::UnawareGoalHandleError If the the goal handle is unaware of the result.
* \return A future to the result.
*/
std::shared_future<WrappedResult>
async_result();

/// Get the goal status code.
int8_t
get_status();

/// Check if an action client has subscribed to feedback for the goal.
bool
is_feedback_aware();

/// Check if an action client has requested the result for the goal.
bool
is_result_aware();

Expand Down
7 changes: 7 additions & 0 deletions rclcpp_action/include/rclcpp_action/create_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,13 @@

namespace rclcpp_action
{
/// Create an action client.
/**
* \param[in] node The action client will be added to this node.
* \param[in] name The action name.
* \param[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.
*/
template<typename ActionT>
typename Client<ActionT>::SharedPtr
create_client(
Expand Down
17 changes: 17 additions & 0 deletions rclcpp_action/include/rclcpp_action/create_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,23 @@

namespace rclcpp_action
{
/// Create an action server.
/**
* All provided callback functions must be non-blocking.
*
* \sa Server::Server() for more information.
*
* \param node[in] The action server will be added to this node.
* \param name[in] The action name.
* \param[in] handle_goal A callback that decides if a goal should be accepted or rejected.
* \param[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.
* \param[in] handle_accepted A callback that is called to give the user a handle to the goal.
* \param[in] options options to pass to the underlying `rcl_action_server_t`.
* \param group[in] The action server will be added to this callback group.
* If `nullptr`, then the action server is added to the default callback group.
*/
template<typename ActionT>
typename Server<ActionT>::SharedPtr
create_server(
Expand Down
7 changes: 6 additions & 1 deletion rclcpp_action/include/rclcpp_action/rclcpp_action.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,14 @@
* `rclcpp_action` provides the canonical C++ API for interacting with ROS Actions.
* It consists of these main components:
*
* - TODO(jacobperron): Finish docs
* - Action Client
* - rclcpp_action/client.hpp
* - rclcpp_action/create_client.hpp
* - rclcpp_action/client_goal_handle.hpp
* - Action Server
* - rclcpp_action/server.hpp
* - rclcpp_action/create_server.hpp
* - rclcpp_action/server_goal_handle.hpp
*/

#ifndef RCLCPP_ACTION__RCLCPP_ACTION_HPP_
Expand Down
4 changes: 2 additions & 2 deletions rclcpp_action/include/rclcpp_action/server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ enum class CancelResponse : int8_t
/// \internal
/**
* This class should not be used directly by users writing an action server.
* Instead users should use `rclcpp_action::Server<>`.
* Instead users should use `rclcpp_action::Server`.
*
* Internally, this class is responsible for interfacing with the `rcl_action` API.
*/
Expand Down Expand Up @@ -288,7 +288,7 @@ class Server : public ServerBase, public std::enable_shared_from_this<Server<Act
* - one to accept or reject requests to cancel a goal,
* - one to receive a goal handle after a goal has been accepted.
* All callbacks must be non-blocking.
* The result of a goal should be set using methods on `rclcpp_action::ServerGoalHandle<>`.
* The result of a goal should be set using methods on `rclcpp_action::ServerGoalHandle`.
*
* \param[in] node_base a pointer to the base interface of a node.
* \param[in] node_clock a pointer to an interface that allows getting a node's clock.
Expand Down
24 changes: 14 additions & 10 deletions rclcpp_action/include/rclcpp_action/server_goal_handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -123,10 +123,10 @@ class Server;
/// 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.
* The class `rclcpp_action::Server<>` will create an instance and give it to the user in their
* `handle_accepted` callback.
* 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`.
Expand All @@ -138,9 +138,10 @@ class ServerGoalHandle : public ServerGoalHandleBase
/// 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
* If execution of a goal is deferred then `ServerGoalHandle::set_executing()` must be called
* first.
* `std::runtime_error` is raised if the goal is in any state besides executing.
*
* \throws std::runtime_error If the goal is in any state besides executing.
*
* \param[in] feedback_msg the message to publish to clients.
*/
Expand All @@ -153,13 +154,13 @@ class ServerGoalHandle : public ServerGoalHandleBase
publish_feedback_(feedback_message);
}

// TODO(sloretz) which exception is raised?
/// 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.
* An exception is raised if the goal is in any state besides executing.
*
* \throws rclcpp::exceptions::RCLError If the goal is in any state besides executing.
*
* \param[in] result_msg the final result to send to clients.
*/
Expand All @@ -173,12 +174,13 @@ class ServerGoalHandle : public ServerGoalHandleBase
on_terminal_state_(uuid_, response);
}

/// Indicate that a goal has been reached.
/// 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.
* An exception is raised if the goal is in any state besides executing.
*
* \throws rclcpp::exceptions::RCLError If the goal is in any state besides executing.
*
* \param[in] result_msg the final result to send to clients.
*/
Expand All @@ -197,7 +199,8 @@ class ServerGoalHandle : public ServerGoalHandleBase
* 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.
* An exception is raised if the goal is in any state besides executing or pending.
*
* \throws rclcpp::exceptions::RCLError If the goal is in any state besides executing.
*
* \param[in] result_msg the final result to send to clients.
*/
Expand All @@ -214,7 +217,8 @@ class ServerGoalHandle : public ServerGoalHandleBase
/// Indicate that the server is starting to execute a goal.
/**
* Only call this if the goal is pending.
* An exception is raised if the goal is in any state besides pending.
*
* \throws rclcpp::exceptions::RCLError If the goal is in any state besides executing.
*/
void
set_executing()
Expand Down

0 comments on commit 569c228

Please sign in to comment.