Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Improved rclcpp docblock #1127

Merged
merged 4 commits into from
May 28, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
25 changes: 25 additions & 0 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,7 @@ class ClientBase
/// Wait for a service to be ready.
/**
* \param timeout maximum time to wait
* \return `true` if the service is ready and the timeout is not over, `false` otherwise
*/
template<typename RepT = int64_t, typename RatioT = std::milli>
bool
Expand Down Expand Up @@ -194,6 +195,17 @@ class Client : public ClientBase

RCLCPP_SMART_PTR_DEFINITIONS(Client)

/// Default constructor.
/**
* The constructor for a Client is almost never called directly.
* Instead, clients should be instantiated through the function
* rclcpp::create_client().
*
* \param[in] node_base NodeBaseInterface pointer that is used in part of the setup.
* \param[in] node_graph The node graph interface of the corresponding node.
* \param[in] service_name Name of the topic to publish to.
* \param[in] client_options options for the subscription.
*/
Client(
rclcpp::node_interfaces::NodeBaseInterface * node_base,
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
Expand Down Expand Up @@ -248,12 +260,20 @@ class Client : public ClientBase
return this->take_type_erased_response(&response_out, request_header_out);
}

/// Create a shared pointer with the response type
/**
* \return shared pointer with the response type
*/
std::shared_ptr<void>
create_response() override
{
return std::shared_ptr<void>(new typename ServiceT::Response());
}

/// Create a shared pointer with a rmw_request_id_t
/**
* \return shared pointer with a rmw_request_id_t
*/
std::shared_ptr<rmw_request_id_t>
create_request_header() override
{
Expand All @@ -262,6 +282,11 @@ class Client : public ClientBase
return std::shared_ptr<rmw_request_id_t>(new rmw_request_id_t);
}

/// Handle a server response
/**
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
* \param[in] request_header used to check if the secuence number is valid
* \param[in] response message with the server response
*/
void
handle_response(
std::shared_ptr<rmw_request_id_t> request_header,
Expand Down
6 changes: 6 additions & 0 deletions rclcpp/include/rclcpp/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,9 @@ class Context : public std::enable_shared_from_this<Context>
* \param[in] argv argument array which may contain arguments intended for ROS
* \param[in] init_options initialization options for rclcpp and underlying layers
* \throw ContextAlreadyInitialized if called if init is called more than once
* \throws anything rclcpp::exceptions::throw_from_rcl_error can throw.
* \throws std::runtime_error if the global logging configure mutex is NULL
* \throws exceptions::UnknownROSArgsError if there are unknown ROS arguments
*/
RCLCPP_PUBLIC
virtual
Expand Down Expand Up @@ -260,6 +263,7 @@ class Context : public std::enable_shared_from_this<Context>
* \param[in] wait_set Pointer to the rcl_wait_set_t that will be using the
* resulting guard condition.
* \return Pointer to the guard condition.
* \throws anything rclcpp::exceptions::throw_from_rcl_error can throw.
*/
RCLCPP_PUBLIC
rcl_guard_condition_t *
Expand All @@ -279,6 +283,8 @@ class Context : public std::enable_shared_from_this<Context>
*
* \param[in] wait_set Pointer to the rcl_wait_set_t that was using the
* resulting guard condition.
* \throws anything rclcpp::exceptions::throw_from_rcl_error can throw.
* \throws std::runtime_error if a nonexistent wait set is trying to release sigint guard condition.
*/
RCLCPP_PUBLIC
void
Expand Down
16 changes: 16 additions & 0 deletions rclcpp/include/rclcpp/event.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,17 +29,33 @@ class Event
public:
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Event)

/// Default construct
/**
* Set the default value to false
*/
RCLCPP_PUBLIC
Event();

/// Set the Event state value to true
/**
* \return The state value before the call.
*/
RCLCPP_PUBLIC
bool
set();

/// Get the state value of the Event
/**
* \return the Event state value
*/
RCLCPP_PUBLIC
bool
check();

/// Get the state value of the Event and set to false
/**
* \return the Event state value
*/
RCLCPP_PUBLIC
bool
check_and_clear();
Expand Down
19 changes: 17 additions & 2 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,9 @@ class Executor
add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true);

/// Convenience function which takes Node and forwards NodeBaseInterface.
/**
* \see rclcpp::Executor::add_node
*/
RCLCPP_PUBLIC
virtual void
add_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify = true);
Expand All @@ -104,6 +107,9 @@ class Executor
remove_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify = true);

/// Convenience function which takes Node and forwards NodeBaseInterface.
/**
* \see rclcpp::Executor::remove_node
*/
RCLCPP_PUBLIC
virtual void
remove_node(std::shared_ptr<rclcpp::Node> node_ptr, bool notify = true);
Expand Down Expand Up @@ -232,7 +238,10 @@ class Executor
}

/// Cancel any running spin* function, causing it to return.
/* This function can be called asynchonously from any thread. */
/**
* This function can be called asynchonously from any thread.
* \throws std::runtime_error if there is an issue triggering the guard condition
*/
RCLCPP_PUBLIC
void
cancel();
Expand All @@ -242,6 +251,7 @@ class Executor
* Switching the memory strategy while the executor is spinning in another threading could have
* unintended consequences.
* \param[in] memory_strategy Shared pointer to the memory strategy to set.
* \throws std::runtime_error if memory_strategy is null
*/
RCLCPP_PUBLIC
void
Expand All @@ -255,8 +265,10 @@ class Executor
std::chrono::nanoseconds timeout);

/// Find the next available executable and do the work associated with it.
/** \param[in] any_exec Union structure that can hold any executable type (timer, subscription,
/**
* \param[in] any_exec Union structure that can hold any executable type (timer, subscription,
* service, client).
* \throws std::runtime_error if there is an issue triggering the guard condition
*/
RCLCPP_PUBLIC
void
Expand All @@ -279,6 +291,9 @@ class Executor
static void
execute_client(rclcpp::ClientBase::SharedPtr client);

/**
* \throws std::runtime_error if the wait set can be cleared
*/
RCLCPP_PUBLIC
void
wait_for_work(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
Expand Down
4 changes: 4 additions & 0 deletions rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,10 @@ class MultiThreadedExecutor : public rclcpp::Executor
RCLCPP_PUBLIC
virtual ~MultiThreadedExecutor();

/**
* \sa rclcpp::Executor:spin() for more details
* \throws std::runtime_error when spin() called while already spinning
*/
RCLCPP_PUBLIC
void
spin() override;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ class SingleThreadedExecutor : public rclcpp::Executor
* the process until canceled.
* It may be interrupt by a call to rclcpp::Executor::cancel() or by ctrl-c
* if the associated context is configured to shutdown on SIGINT.
* \throws std::runtime_error when spin() called while already spinning
*/
RCLCPP_PUBLIC
void
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,13 @@ class StaticExecutorEntitiesCollector final
// Destructor
~StaticExecutorEntitiesCollector();

/// Initialize StaticExecutorEntitiesCollector
/**
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
* \param p_wait_set A reference to the wait set to be used in the executor
* \param memory_strategy Shared pointer to the memory strategy to set.
* \param executor_guard_condition executor's guard condition
* \throws std::runtime_error if memory strategy is null
*/
RCLCPP_PUBLIC
void
init(
Expand All @@ -67,16 +74,26 @@ class StaticExecutorEntitiesCollector final
fill_executable_list();

/// Function to reallocate space for entities in the wait set.
/**
* \throws std::runtime_error if wait set couldn't be cleared or resized.
*/
RCLCPP_PUBLIC
void
prepare_wait_set();

/// Function to add_handles_to_wait_set and wait for work and
// block until the wait set is ready or until the timeout has been exceeded.
/**
* block until the wait set is ready or until the timeout has been exceeded.
* \throws std::runtime_error if wait set couldn't be cleared or filled.
* \throws any rcl errors from rcl_wait, \sa rclcpp::exceptions::throw_from_rcl_error()
*/
RCLCPP_PUBLIC
void
refresh_wait_set(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));

/**
* \throws std::runtime_error if it couldn't add guard condition to wait set
*/
RCLCPP_PUBLIC
bool
add_to_wait_set(rcl_wait_set_t * wait_set) override;
Expand All @@ -85,11 +102,19 @@ class StaticExecutorEntitiesCollector final
size_t
get_number_of_ready_guard_conditions() override;

/**
* \sa rclcpp::Executor::add_node()
* \throw std::runtime_error if node was already added
*/
RCLCPP_PUBLIC
void
add_node(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);

/**
* \sa rclcpp::Executor::remove_node()
* \throw std::runtime_error if no guard condition is associated with node.
*/
RCLCPP_PUBLIC
bool
remove_node(
Expand All @@ -105,42 +130,87 @@ class StaticExecutorEntitiesCollector final
bool
is_ready(rcl_wait_set_t * wait_set) override;

/// Return number of timers
/**
* \return number of timers
*/
RCLCPP_PUBLIC
size_t
get_number_of_timers() {return exec_list_.number_of_timers;}

/// Return number of subscriptions
/**
* \return number of subscriptions
*/
RCLCPP_PUBLIC
size_t
get_number_of_subscriptions() {return exec_list_.number_of_subscriptions;}

/// Return number of services
/**
* \return number of services
*/
RCLCPP_PUBLIC
size_t
get_number_of_services() {return exec_list_.number_of_services;}

/// Return number of clients
/**
* \return number of clients
*/
RCLCPP_PUBLIC
size_t
get_number_of_clients() {return exec_list_.number_of_clients;}

/// Return number of waitables
/**
* \return number of waitables
*/
RCLCPP_PUBLIC
size_t
get_number_of_waitables() {return exec_list_.number_of_waitables;}

/** Return a SubscritionBase Sharedptr by index.
* \param[in] i The index of the SubscritionBase
* \return a SubscritionBase shared pointer
* \throws std::out_of_range if the argument is higher than the size of the structrue.
*/
RCLCPP_PUBLIC
rclcpp::SubscriptionBase::SharedPtr
get_subscription(size_t i) {return exec_list_.subscription[i];}

/** Return a TimerBase Sharedptr by index.
* \param[in] i The index of the TimerBase
* \return a TimerBase shared pointer
* \throws std::out_of_range if the argument is higher than the size.
*/
RCLCPP_PUBLIC
rclcpp::TimerBase::SharedPtr
get_timer(size_t i) {return exec_list_.timer[i];}

/** Return a ServiceBase Sharedptr by index.
* \param[in] i The index of the ServiceBase
* \return a ServiceBase shared pointer
* \throws std::out_of_range if the argument is higher than the size.
*/
RCLCPP_PUBLIC
rclcpp::ServiceBase::SharedPtr
get_service(size_t i) {return exec_list_.service[i];}

/** Return a ClientBase Sharedptr by index
* \param[in] i The index of the ClientBase
* \return a ClientBase shared pointer
* \throws std::out_of_range if the argument is higher than the size.
*/
RCLCPP_PUBLIC
rclcpp::ClientBase::SharedPtr
get_client(size_t i) {return exec_list_.client[i];}

/** Return a Waitable Sharedptr by index
* \param[in] i The index of the Waitable
* \return a Waitable shared pointer
* \throws std::out_of_range if the argument is higher than the size.
*/
RCLCPP_PUBLIC
rclcpp::Waitable::SharedPtr
get_waitable(size_t i) {return exec_list_.waitable[i];}
Expand Down
Loading