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

Added docblock in rclcpp #1103

Merged
merged 3 commits into from
May 6, 2020
Merged
Show file tree
Hide file tree
Changes from 2 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
20 changes: 20 additions & 0 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,22 +84,42 @@ class ClientBase
bool
take_type_erased_response(void * response_out, rmw_request_id_t & request_header_out);

/// Return the name of the service.
/** \return The name of the service. */
RCLCPP_PUBLIC
const char *
get_service_name() const;

/// Return the rcl_client_t client handle in a std::shared_ptr.
/**
* This handle remains valid after the Client is destroyed.
* The actual rcl client is not finalized until it is out of scope everywhere.
*/
RCLCPP_PUBLIC
std::shared_ptr<rcl_client_t>
get_client_handle();

/// Return the rcl_client_t client handle in a std::shared_ptr.
/**
* This handle remains valid after the Client is destroyed.
* The actual rcl client is not finalized until it is out of scope everywhere.
*/
RCLCPP_PUBLIC
std::shared_ptr<const rcl_client_t>
get_client_handle() const;

/// Return if the service is ready.
/**
* \return `true` if the service is ready, `false` otherwise
*/
RCLCPP_PUBLIC
bool
service_is_ready() const;

/// Wait for a service to be ready.
/**
* \param timeout maximum time to wait
*/
template<typename RepT = int64_t, typename RatioT = std::milli>
bool
wait_for_service(
Expand Down
2 changes: 2 additions & 0 deletions rclcpp/include/rclcpp/clock.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,7 @@ class Clock
bool
ros_time_is_active();

/// Return the rcl_clock_t clock handle
RCLCPP_PUBLIC
rcl_clock_t *
get_clock_handle() noexcept;
Expand All @@ -97,6 +98,7 @@ class Clock
rcl_clock_type_t
get_clock_type() const noexcept;

/// Get the clock's mutex
RCLCPP_PUBLIC
std::mutex &
get_clock_mutex() noexcept;
Expand Down
38 changes: 33 additions & 5 deletions rclcpp/include/rclcpp/duration.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,22 @@ namespace rclcpp
class RCLCPP_PUBLIC Duration
{
public:
/// Duration constructor.
/**
* Initializes the time values for seconds and nanoseconds individually.
* Large values for nsecs are wrapped automatically with the remainder added to secs.
* Both inputs must be integers.
* Seconds can be negative.
*
* \param seconds time in seconds
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
* \param nanoseconds time in nanoseconds
*/
Duration(int32_t seconds, uint32_t nanoseconds);

// This constructor matches any numeric value - ints or floats
// This constructor matches any numeric value - ints or floats.
explicit Duration(rcl_duration_value_t nanoseconds);

// This constructor matches std::chrono::nanoseconds.
explicit Duration(std::chrono::nanoseconds nanoseconds);

// This constructor matches any std::chrono value other than nanoseconds
Expand All @@ -44,6 +55,10 @@ class RCLCPP_PUBLIC Duration
// cppcheck-suppress noExplicitConstructor
Duration(const builtin_interfaces::msg::Duration & duration_msg); // NOLINT(runtime/explicit)

/// Time constructor
/**
* \param duration rcl_duration_t structure to copy.
*/
explicit Duration(const rcl_duration_t & duration);

Duration(const Duration & rhs);
Expand Down Expand Up @@ -80,33 +95,46 @@ class RCLCPP_PUBLIC Duration
Duration
operator-(const rclcpp::Duration & rhs) const;

/// Get the maximum representable value.
/**
* \return the maximum representable value
*/
static
Duration
max();

Duration
operator*(double scale) const;

/// Get duration in nanosecods
/**
* \return the duration in nanoseconds as a rcl_duration_value_t.
*/
rcl_duration_value_t
nanoseconds() const;

/// \return the duration in seconds as a floating point number.
/// \warning Depending on sizeof(double) there could be significant precision loss.
/// When an exact time is required use nanoseconds() instead.
/// Get duration in seconds
/**
* \warning Depending on sizeof(double) there could be significant precision loss.
* When an exact time is required use nanoseconds() instead.
* \return the duration in seconds as a floating point number.
*/
double
seconds() const;

// Create a duration object from a floating point number representing seconds
/// Create a duration object from a floating point number representing seconds
static Duration
from_seconds(double seconds);

/// Convert Duration in to std::chrono.
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
template<class DurationT>
DurationT
to_chrono() const
{
return std::chrono::duration_cast<DurationT>(std::chrono::nanoseconds(this->nanoseconds()));
}

/// Convert Duration into rmw_time_t.
rmw_time_t
to_rmw_time() const;

Expand Down
19 changes: 16 additions & 3 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,8 +186,8 @@ class Node : public std::enable_shared_from_this<Node>
/// Create and return a Subscription.
/**
* \param[in] topic_name The topic to subscribe on.
* \param[in] qos QoS profile for Subcription.
* \param[in] callback The user-defined callback function to receive a message
* \param[in] qos_history_depth The depth of the subscription's incoming message queue.
* \param[in] options Additional options for the creation of the Subscription.
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
* \return Shared pointer to the created subscription.
Expand Down Expand Up @@ -229,15 +229,28 @@ class Node : public std::enable_shared_from_this<Node>
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr);

/* Create and return a Client. */
/// Create and return a Client.
/**
* \param[in] service_name The topic to service on.
* \param[in] rmw_qos_profile_t Quality of service profile for client.
* \param[in] group Callback group to call the service.
* \return Shared pointer to the created client.
*/
template<typename ServiceT>
typename rclcpp::Client<ServiceT>::SharedPtr
create_client(
const std::string & service_name,
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
rclcpp::CallbackGroup::SharedPtr group = nullptr);

/* Create and return a Service. */
/// Create and return a Service.
/**
* \param[in] service_name The topic to service on.
* \param[in] callback User-defined callback function.
* \param[in] rmw_qos_profile_t Quality of service profile for client.
* \param[in] group Callback group to call the service.
* \return Shared pointer to the created service.
*/
template<typename ServiceT, typename CallbackT>
typename rclcpp::Service<ServiceT>::SharedPtr
create_service(
Expand Down
46 changes: 46 additions & 0 deletions rclcpp/include/rclcpp/parameter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,18 +83,22 @@ class Parameter
bool
operator!=(const Parameter & rhs) const;

/// Get the type of the parameter
RCLCPP_PUBLIC
ParameterType
get_type() const;

/// Get the type name of the parameter
RCLCPP_PUBLIC
std::string
get_type_name() const;

/// Get the name of the parameter
RCLCPP_PUBLIC
const std::string &
get_name() const;

/// Get value of parameter as a parameter message.
RCLCPP_PUBLIC
rcl_interfaces::msg::ParameterValue
get_value_message() const;
Expand All @@ -105,6 +109,9 @@ class Parameter
get_parameter_value() const;

/// Get value of parameter using rclcpp::ParameterType as template argument.
/**
* \throws rclcpp::exceptions::InvalidParameterTypeException if the type doesn't match
*/
template<ParameterType ParamT>
decltype(auto)
get_value() const
Expand All @@ -117,50 +124,89 @@ class Parameter
decltype(auto)
get_value() const;

/// Get value of parameter as boolean.
ahcorde marked this conversation as resolved.
Show resolved Hide resolved
/**
* \throws rclcpp::ParameterTypeException if the type doesn't match
*/
RCLCPP_PUBLIC
bool
as_bool() const;

/// Get value of parameter as integer.
/**
* \throws rclcpp::ParameterTypeException if the type doesn't match
*/
RCLCPP_PUBLIC
int64_t
as_int() const;

/// Get value of parameter as double.
/**
* \throws rclcpp::ParameterTypeException if the type doesn't match
*/
RCLCPP_PUBLIC
double
as_double() const;

/// Get value of parameter as string.
/**
* \throws rclcpp::ParameterTypeException if the type doesn't match
*/
RCLCPP_PUBLIC
const std::string &
as_string() const;

/// Get value of parameter as byte array (vector<uint8_t>).
/**
* \throws rclcpp::ParameterTypeException if the type doesn't match
*/
RCLCPP_PUBLIC
const std::vector<uint8_t> &
as_byte_array() const;

/// Get value of parameter as bool array (vector<bool>).
/**
* \throws rclcpp::ParameterTypeException if the type doesn't match
*/
RCLCPP_PUBLIC
const std::vector<bool> &
as_bool_array() const;

/// Get value of parameter as integer array (vector<int64_t>).
/**
* \throws rclcpp::ParameterTypeException if the type doesn't match
*/
RCLCPP_PUBLIC
const std::vector<int64_t> &
as_integer_array() const;

/// Get value of parameter as double array (vector<double>).
/**
* \throws rclcpp::ParameterTypeException if the type doesn't match
*/
RCLCPP_PUBLIC
const std::vector<double> &
as_double_array() const;

/// Get value of parameter as string array (vector<std::string>).
/**
* \throws rclcpp::ParameterTypeException if the type doesn't match
*/
RCLCPP_PUBLIC
const std::vector<std::string> &
as_string_array() const;

/// Convert a parameter message in a Parameter class object.
RCLCPP_PUBLIC
static Parameter
from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter);

/// Convert the class in a parameter message.
RCLCPP_PUBLIC
rcl_interfaces::msg::Parameter
to_parameter_msg() const;

/// Get value of parameter as a string.
RCLCPP_PUBLIC
std::string
value_to_string() const;
Expand Down
11 changes: 11 additions & 0 deletions rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,17 @@ class Publisher : public PublisherBase

RCLCPP_SMART_PTR_DEFINITIONS(Publisher<MessageT, AllocatorT>)

/// Default constructor.
/**
* The constructor for a Publisher is almost never called directly.
* Instead, subscriptions should be instantiated through the function
* rclcpp::create_publisher().
*
* \param[in] node_base NodeBaseInterface pointer that is used in part of the setup.
* \param[in] topic Name of the topic to publish to.
* \param[in] qos QoS profile for Subcription.
* \param[in] options options for the subscription.
*/
Publisher(
rclcpp::node_interfaces::NodeBaseInterface * node_base,
const std::string & topic,
Expand Down
Loading