Added docblock in rclcpp (#1103)
* Added docblock in rclcpp Signed-off-by: ahcorde <ahcorde@gmail.com> * Added feedback Signed-off-by: ahcorde <ahcorde@gmail.com> * Added feedback Signed-off-by: ahcorde <ahcorde@gmail.com>
This commit is contained in:
parent
e2dbc5d5d5
commit
f160a8bc1d
14 changed files with 312 additions and 12 deletions
|
@ -84,22 +84,42 @@ public:
|
||||||
bool
|
bool
|
||||||
take_type_erased_response(void * response_out, rmw_request_id_t & request_header_out);
|
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
|
RCLCPP_PUBLIC
|
||||||
const char *
|
const char *
|
||||||
get_service_name() const;
|
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
|
RCLCPP_PUBLIC
|
||||||
std::shared_ptr<rcl_client_t>
|
std::shared_ptr<rcl_client_t>
|
||||||
get_client_handle();
|
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
|
RCLCPP_PUBLIC
|
||||||
std::shared_ptr<const rcl_client_t>
|
std::shared_ptr<const rcl_client_t>
|
||||||
get_client_handle() const;
|
get_client_handle() const;
|
||||||
|
|
||||||
|
/// Return if the service is ready.
|
||||||
|
/**
|
||||||
|
* \return `true` if the service is ready, `false` otherwise
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
bool
|
bool
|
||||||
service_is_ready() const;
|
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>
|
template<typename RepT = int64_t, typename RatioT = std::milli>
|
||||||
bool
|
bool
|
||||||
wait_for_service(
|
wait_for_service(
|
||||||
|
|
|
@ -89,6 +89,7 @@ public:
|
||||||
bool
|
bool
|
||||||
ros_time_is_active();
|
ros_time_is_active();
|
||||||
|
|
||||||
|
/// Return the rcl_clock_t clock handle
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
rcl_clock_t *
|
rcl_clock_t *
|
||||||
get_clock_handle() noexcept;
|
get_clock_handle() noexcept;
|
||||||
|
@ -97,6 +98,7 @@ public:
|
||||||
rcl_clock_type_t
|
rcl_clock_type_t
|
||||||
get_clock_type() const noexcept;
|
get_clock_type() const noexcept;
|
||||||
|
|
||||||
|
/// Get the clock's mutex
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
std::mutex &
|
std::mutex &
|
||||||
get_clock_mutex() noexcept;
|
get_clock_mutex() noexcept;
|
||||||
|
|
|
@ -26,11 +26,22 @@ namespace rclcpp
|
||||||
class RCLCPP_PUBLIC Duration
|
class RCLCPP_PUBLIC Duration
|
||||||
{
|
{
|
||||||
public:
|
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
|
||||||
|
* \param nanoseconds time in nanoseconds
|
||||||
|
*/
|
||||||
Duration(int32_t seconds, uint32_t 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);
|
explicit Duration(rcl_duration_value_t nanoseconds);
|
||||||
|
|
||||||
|
// This constructor matches std::chrono::nanoseconds.
|
||||||
explicit Duration(std::chrono::nanoseconds nanoseconds);
|
explicit Duration(std::chrono::nanoseconds nanoseconds);
|
||||||
|
|
||||||
// This constructor matches any std::chrono value other than nanoseconds
|
// This constructor matches any std::chrono value other than nanoseconds
|
||||||
|
@ -44,6 +55,10 @@ public:
|
||||||
// cppcheck-suppress noExplicitConstructor
|
// cppcheck-suppress noExplicitConstructor
|
||||||
Duration(const builtin_interfaces::msg::Duration & duration_msg); // NOLINT(runtime/explicit)
|
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);
|
explicit Duration(const rcl_duration_t & duration);
|
||||||
|
|
||||||
Duration(const Duration & rhs);
|
Duration(const Duration & rhs);
|
||||||
|
@ -80,6 +95,10 @@ public:
|
||||||
Duration
|
Duration
|
||||||
operator-(const rclcpp::Duration & rhs) const;
|
operator-(const rclcpp::Duration & rhs) const;
|
||||||
|
|
||||||
|
/// Get the maximum representable value.
|
||||||
|
/**
|
||||||
|
* \return the maximum representable value
|
||||||
|
*/
|
||||||
static
|
static
|
||||||
Duration
|
Duration
|
||||||
max();
|
max();
|
||||||
|
@ -87,19 +106,27 @@ public:
|
||||||
Duration
|
Duration
|
||||||
operator*(double scale) const;
|
operator*(double scale) const;
|
||||||
|
|
||||||
|
/// Get duration in nanosecods
|
||||||
|
/**
|
||||||
|
* \return the duration in nanoseconds as a rcl_duration_value_t.
|
||||||
|
*/
|
||||||
rcl_duration_value_t
|
rcl_duration_value_t
|
||||||
nanoseconds() const;
|
nanoseconds() const;
|
||||||
|
|
||||||
/// \return the duration in seconds as a floating point number.
|
/// Get duration in seconds
|
||||||
/// \warning Depending on sizeof(double) there could be significant precision loss.
|
/**
|
||||||
/// When an exact time is required use nanoseconds() instead.
|
* \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
|
double
|
||||||
seconds() const;
|
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
|
static Duration
|
||||||
from_seconds(double seconds);
|
from_seconds(double seconds);
|
||||||
|
|
||||||
|
/// Convert Duration into a std::chrono::Duration.
|
||||||
template<class DurationT>
|
template<class DurationT>
|
||||||
DurationT
|
DurationT
|
||||||
to_chrono() const
|
to_chrono() const
|
||||||
|
@ -107,6 +134,7 @@ public:
|
||||||
return std::chrono::duration_cast<DurationT>(std::chrono::nanoseconds(this->nanoseconds()));
|
return std::chrono::duration_cast<DurationT>(std::chrono::nanoseconds(this->nanoseconds()));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/// Convert Duration into rmw_time_t.
|
||||||
rmw_time_t
|
rmw_time_t
|
||||||
to_rmw_time() const;
|
to_rmw_time() const;
|
||||||
|
|
||||||
|
|
|
@ -186,8 +186,8 @@ public:
|
||||||
/// Create and return a Subscription.
|
/// Create and return a Subscription.
|
||||||
/**
|
/**
|
||||||
* \param[in] topic_name The topic to subscribe on.
|
* \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] 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] options Additional options for the creation of the Subscription.
|
||||||
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
|
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
|
||||||
* \return Shared pointer to the created subscription.
|
* \return Shared pointer to the created subscription.
|
||||||
|
@ -229,7 +229,13 @@ public:
|
||||||
CallbackT callback,
|
CallbackT callback,
|
||||||
rclcpp::CallbackGroup::SharedPtr group = nullptr);
|
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>
|
template<typename ServiceT>
|
||||||
typename rclcpp::Client<ServiceT>::SharedPtr
|
typename rclcpp::Client<ServiceT>::SharedPtr
|
||||||
create_client(
|
create_client(
|
||||||
|
@ -237,7 +243,14 @@ public:
|
||||||
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
|
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_services_default,
|
||||||
rclcpp::CallbackGroup::SharedPtr group = nullptr);
|
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>
|
template<typename ServiceT, typename CallbackT>
|
||||||
typename rclcpp::Service<ServiceT>::SharedPtr
|
typename rclcpp::Service<ServiceT>::SharedPtr
|
||||||
create_service(
|
create_service(
|
||||||
|
|
|
@ -83,18 +83,22 @@ public:
|
||||||
bool
|
bool
|
||||||
operator!=(const Parameter & rhs) const;
|
operator!=(const Parameter & rhs) const;
|
||||||
|
|
||||||
|
/// Get the type of the parameter
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
ParameterType
|
ParameterType
|
||||||
get_type() const;
|
get_type() const;
|
||||||
|
|
||||||
|
/// Get the type name of the parameter
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
std::string
|
std::string
|
||||||
get_type_name() const;
|
get_type_name() const;
|
||||||
|
|
||||||
|
/// Get the name of the parameter
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
const std::string &
|
const std::string &
|
||||||
get_name() const;
|
get_name() const;
|
||||||
|
|
||||||
|
/// Get value of parameter as a parameter message.
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
rcl_interfaces::msg::ParameterValue
|
rcl_interfaces::msg::ParameterValue
|
||||||
get_value_message() const;
|
get_value_message() const;
|
||||||
|
@ -105,6 +109,9 @@ public:
|
||||||
get_parameter_value() const;
|
get_parameter_value() const;
|
||||||
|
|
||||||
/// Get value of parameter using rclcpp::ParameterType as template argument.
|
/// Get value of parameter using rclcpp::ParameterType as template argument.
|
||||||
|
/**
|
||||||
|
* \throws rclcpp::exceptions::InvalidParameterTypeException if the type doesn't match
|
||||||
|
*/
|
||||||
template<ParameterType ParamT>
|
template<ParameterType ParamT>
|
||||||
decltype(auto)
|
decltype(auto)
|
||||||
get_value() const
|
get_value() const
|
||||||
|
@ -117,50 +124,89 @@ public:
|
||||||
decltype(auto)
|
decltype(auto)
|
||||||
get_value() const;
|
get_value() const;
|
||||||
|
|
||||||
|
/// Get value of parameter as boolean.
|
||||||
|
/**
|
||||||
|
* \throws rclcpp::ParameterTypeException if the type doesn't match
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
bool
|
bool
|
||||||
as_bool() const;
|
as_bool() const;
|
||||||
|
|
||||||
|
/// Get value of parameter as integer.
|
||||||
|
/**
|
||||||
|
* \throws rclcpp::ParameterTypeException if the type doesn't match
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
int64_t
|
int64_t
|
||||||
as_int() const;
|
as_int() const;
|
||||||
|
|
||||||
|
/// Get value of parameter as double.
|
||||||
|
/**
|
||||||
|
* \throws rclcpp::ParameterTypeException if the type doesn't match
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
double
|
double
|
||||||
as_double() const;
|
as_double() const;
|
||||||
|
|
||||||
|
/// Get value of parameter as string.
|
||||||
|
/**
|
||||||
|
* \throws rclcpp::ParameterTypeException if the type doesn't match
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
const std::string &
|
const std::string &
|
||||||
as_string() const;
|
as_string() const;
|
||||||
|
|
||||||
|
/// Get value of parameter as byte array (vector<uint8_t>).
|
||||||
|
/**
|
||||||
|
* \throws rclcpp::ParameterTypeException if the type doesn't match
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
const std::vector<uint8_t> &
|
const std::vector<uint8_t> &
|
||||||
as_byte_array() const;
|
as_byte_array() const;
|
||||||
|
|
||||||
|
/// Get value of parameter as bool array (vector<bool>).
|
||||||
|
/**
|
||||||
|
* \throws rclcpp::ParameterTypeException if the type doesn't match
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
const std::vector<bool> &
|
const std::vector<bool> &
|
||||||
as_bool_array() const;
|
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
|
RCLCPP_PUBLIC
|
||||||
const std::vector<int64_t> &
|
const std::vector<int64_t> &
|
||||||
as_integer_array() const;
|
as_integer_array() const;
|
||||||
|
|
||||||
|
/// Get value of parameter as double array (vector<double>).
|
||||||
|
/**
|
||||||
|
* \throws rclcpp::ParameterTypeException if the type doesn't match
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
const std::vector<double> &
|
const std::vector<double> &
|
||||||
as_double_array() const;
|
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
|
RCLCPP_PUBLIC
|
||||||
const std::vector<std::string> &
|
const std::vector<std::string> &
|
||||||
as_string_array() const;
|
as_string_array() const;
|
||||||
|
|
||||||
|
/// Convert a parameter message in a Parameter class object.
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
static Parameter
|
static Parameter
|
||||||
from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter);
|
from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter);
|
||||||
|
|
||||||
|
/// Convert the class in a parameter message.
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
rcl_interfaces::msg::Parameter
|
rcl_interfaces::msg::Parameter
|
||||||
to_parameter_msg() const;
|
to_parameter_msg() const;
|
||||||
|
|
||||||
|
/// Get value of parameter as a string.
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
std::string
|
std::string
|
||||||
value_to_string() const;
|
value_to_string() const;
|
||||||
|
|
|
@ -59,6 +59,17 @@ public:
|
||||||
|
|
||||||
RCLCPP_SMART_PTR_DEFINITIONS(Publisher<MessageT, AllocatorT>)
|
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(
|
Publisher(
|
||||||
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
||||||
const std::string & topic,
|
const std::string & topic,
|
||||||
|
|
|
@ -161,6 +161,18 @@ bool operator==(const QoS & left, const QoS & right);
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
bool operator!=(const QoS & left, const QoS & right);
|
bool operator!=(const QoS & left, const QoS & right);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Sensor Data QoS class
|
||||||
|
* - History: Keep last,
|
||||||
|
* - Depth: 5,
|
||||||
|
* - Reliability: Best effort,
|
||||||
|
* - Durability: Volatile,
|
||||||
|
* - Deadline: Default,
|
||||||
|
* - Lifespan: Default,
|
||||||
|
* - Liveliness: System default,
|
||||||
|
* - Liveliness lease duration: default,
|
||||||
|
* - avoid ros namespace conventions: false
|
||||||
|
*/
|
||||||
class RCLCPP_PUBLIC SensorDataQoS : public QoS
|
class RCLCPP_PUBLIC SensorDataQoS : public QoS
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
@ -171,6 +183,18 @@ public:
|
||||||
));
|
));
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Parameters QoS class
|
||||||
|
* - History: Keep last,
|
||||||
|
* - Depth: 1000,
|
||||||
|
* - Reliability: Reliable,
|
||||||
|
* - Durability: Volatile,
|
||||||
|
* - Deadline: Default,
|
||||||
|
* - Lifespan: Default,
|
||||||
|
* - Liveliness: System default,
|
||||||
|
* - Liveliness lease duration: default,
|
||||||
|
* - Avoid ros namespace conventions: false
|
||||||
|
*/
|
||||||
class RCLCPP_PUBLIC ParametersQoS : public QoS
|
class RCLCPP_PUBLIC ParametersQoS : public QoS
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
@ -181,6 +205,18 @@ public:
|
||||||
));
|
));
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Services QoS class
|
||||||
|
* - History: Keep last,
|
||||||
|
* - Depth: 10,
|
||||||
|
* - Reliability: Reliable,
|
||||||
|
* - Durability: Volatile,
|
||||||
|
* - Deadline: Default,
|
||||||
|
* - Lifespan: Default,
|
||||||
|
* - Liveliness: System default,
|
||||||
|
* - Liveliness lease duration: default,
|
||||||
|
* - Avoid ros namespace conventions: false
|
||||||
|
*/
|
||||||
class RCLCPP_PUBLIC ServicesQoS : public QoS
|
class RCLCPP_PUBLIC ServicesQoS : public QoS
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
@ -191,6 +227,18 @@ public:
|
||||||
));
|
));
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Parameter events QoS class
|
||||||
|
* - History: Keep last,
|
||||||
|
* - Depth: 1000,
|
||||||
|
* - Reliability: Reliable,
|
||||||
|
* - Durability: Volatile,
|
||||||
|
* - Deadline: Default,
|
||||||
|
* - Lifespan: Default,
|
||||||
|
* - Liveliness: System default,
|
||||||
|
* - Liveliness lease duration: default,
|
||||||
|
* - Avoid ros namespace conventions: false
|
||||||
|
*/
|
||||||
class RCLCPP_PUBLIC ParameterEventsQoS : public QoS
|
class RCLCPP_PUBLIC ParameterEventsQoS : public QoS
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
@ -201,6 +249,18 @@ public:
|
||||||
));
|
));
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* System defaults QoS class
|
||||||
|
* - History: System default,
|
||||||
|
* - Depth: System default,
|
||||||
|
* - Reliability: System default,
|
||||||
|
* - Durability: System default,
|
||||||
|
* - Deadline: Default,
|
||||||
|
* - Lifespan: Default,
|
||||||
|
* - Liveliness: System default,
|
||||||
|
* - Liveliness lease duration: System default,
|
||||||
|
* - Avoid ros namespace conventions: false
|
||||||
|
*/
|
||||||
class RCLCPP_PUBLIC SystemDefaultsQoS : public QoS
|
class RCLCPP_PUBLIC SystemDefaultsQoS : public QoS
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -128,6 +128,7 @@
|
||||||
* - rclcpp/context.hpp
|
* - rclcpp/context.hpp
|
||||||
* - rclcpp/contexts/default_context.hpp
|
* - rclcpp/contexts/default_context.hpp
|
||||||
* - Various utilities:
|
* - Various utilities:
|
||||||
|
* - rclcpp/duration.hpp
|
||||||
* - rclcpp/function_traits.hpp
|
* - rclcpp/function_traits.hpp
|
||||||
* - rclcpp/macros.hpp
|
* - rclcpp/macros.hpp
|
||||||
* - rclcpp/scope_exit.hpp
|
* - rclcpp/scope_exit.hpp
|
||||||
|
|
|
@ -50,14 +50,26 @@ public:
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
virtual ~ServiceBase();
|
virtual ~ServiceBase();
|
||||||
|
|
||||||
|
/// Return the name of the service.
|
||||||
|
/** \return The name of the service. */
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
const char *
|
const char *
|
||||||
get_service_name();
|
get_service_name();
|
||||||
|
|
||||||
|
/// Return the rcl_service_t service handle in a std::shared_ptr.
|
||||||
|
/**
|
||||||
|
* This handle remains valid after the Service is destroyed.
|
||||||
|
* The actual rcl service is not finalized until it is out of scope everywhere.
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
std::shared_ptr<rcl_service_t>
|
std::shared_ptr<rcl_service_t>
|
||||||
get_service_handle();
|
get_service_handle();
|
||||||
|
|
||||||
|
/// Return the rcl_service_t service handle in a std::shared_ptr.
|
||||||
|
/**
|
||||||
|
* This handle remains valid after the Service is destroyed.
|
||||||
|
* The actual rcl service is not finalized until it is out of scope everywhere.
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
std::shared_ptr<const rcl_service_t>
|
std::shared_ptr<const rcl_service_t>
|
||||||
get_service_handle() const;
|
get_service_handle() const;
|
||||||
|
|
|
@ -90,9 +90,14 @@ public:
|
||||||
* \param[in] node_base NodeBaseInterface pointer that is used in part of the setup.
|
* \param[in] node_base NodeBaseInterface pointer that is used in part of the setup.
|
||||||
* \param[in] type_support_handle rosidl type support struct, for the Message type of the topic.
|
* \param[in] type_support_handle rosidl type support struct, for the Message type of the topic.
|
||||||
* \param[in] topic_name Name of the topic to subscribe to.
|
* \param[in] topic_name Name of the topic to subscribe to.
|
||||||
|
* \param[in] qos QoS profile for Subcription.
|
||||||
* \param[in] callback User defined callback to call when a message is received.
|
* \param[in] callback User defined callback to call when a message is received.
|
||||||
* \param[in] options options for the subscription.
|
* \param[in] options options for the subscription.
|
||||||
* \param[in] message_memory_strategy The memory strategy to be used for managing message memory.
|
* \param[in] message_memory_strategy The memory strategy to be used for managing message memory.
|
||||||
|
* \param[in] subscription_topic_statistics pointer to a topic statistics subcription.
|
||||||
|
* \throws std::invalid_argument if the QoS is uncompatible with intra-process (if one
|
||||||
|
* of the following conditions are true: qos_profile.history == RMW_QOS_POLICY_HISTORY_KEEP_ALL,
|
||||||
|
* qos_profile.depth == 0 or qos_profile.durability != RMW_QOS_POLICY_DURABILITY_VOLATILE).
|
||||||
*/
|
*/
|
||||||
Subscription(
|
Subscription(
|
||||||
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
rclcpp::node_interfaces::NodeBaseInterface * node_base,
|
||||||
|
|
|
@ -89,6 +89,10 @@ struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase
|
||||||
{}
|
{}
|
||||||
|
|
||||||
/// Convert this class, with a rclcpp::QoS, into an rcl_subscription_options_t.
|
/// Convert this class, with a rclcpp::QoS, into an rcl_subscription_options_t.
|
||||||
|
/**
|
||||||
|
* \param qos QoS profile for subcription.
|
||||||
|
* \return rcl_subscription_options_t structure based on the rclcpp::QoS
|
||||||
|
*/
|
||||||
template<typename MessageT>
|
template<typename MessageT>
|
||||||
rcl_subscription_options_t
|
rcl_subscription_options_t
|
||||||
to_rcl_subscription_options(const rclcpp::QoS & qos) const
|
to_rcl_subscription_options(const rclcpp::QoS & qos) const
|
||||||
|
|
|
@ -31,26 +31,54 @@ class Clock;
|
||||||
class Time
|
class Time
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
/// Time constructor
|
||||||
|
/**
|
||||||
|
* Initializes the time values for seconds and nanoseconds individually.
|
||||||
|
* Large values for nanoseconds are wrapped automatically with the remainder added to seconds.
|
||||||
|
* Both inputs must be integers.
|
||||||
|
*
|
||||||
|
* \param seconds part of the time in seconds since time epoch
|
||||||
|
* \param nanoseconds part of the time in nanoseconds since time epoch
|
||||||
|
* \param clock_type clock type
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
Time(int32_t seconds, uint32_t nanoseconds, rcl_clock_type_t clock_type = RCL_SYSTEM_TIME);
|
Time(int32_t seconds, uint32_t nanoseconds, rcl_clock_type_t clock_type = RCL_SYSTEM_TIME);
|
||||||
|
|
||||||
|
/// Time constructor
|
||||||
|
/**
|
||||||
|
* \param nanoseconds since time epoch
|
||||||
|
* \param clock_type clock type
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock = RCL_SYSTEM_TIME);
|
explicit Time(int64_t nanoseconds = 0, rcl_clock_type_t clock = RCL_SYSTEM_TIME);
|
||||||
|
|
||||||
|
/// Copy constructor
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
Time(const Time & rhs);
|
Time(const Time & rhs);
|
||||||
|
|
||||||
|
/// Time constructor
|
||||||
|
/**
|
||||||
|
* \param time_msg builtin_interfaces time message to copy
|
||||||
|
* \param clock_type clock type
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
Time(
|
Time(
|
||||||
const builtin_interfaces::msg::Time & time_msg,
|
const builtin_interfaces::msg::Time & time_msg,
|
||||||
rcl_clock_type_t ros_time = RCL_ROS_TIME);
|
rcl_clock_type_t ros_time = RCL_ROS_TIME);
|
||||||
|
|
||||||
|
/// Time constructor
|
||||||
|
/**
|
||||||
|
* \param time_point rcl_time_point_t structure to copy
|
||||||
|
* \param clock_type clock type
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
explicit Time(const rcl_time_point_t & time_point);
|
explicit Time(const rcl_time_point_t & time_point);
|
||||||
|
|
||||||
|
/// Time destructor
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
virtual ~Time();
|
virtual ~Time();
|
||||||
|
|
||||||
|
/// Return a builtin_interfaces::msg::Time object based
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
operator builtin_interfaces::msg::Time() const;
|
operator builtin_interfaces::msg::Time() const;
|
||||||
|
|
||||||
|
@ -106,21 +134,37 @@ public:
|
||||||
Time &
|
Time &
|
||||||
operator-=(const rclcpp::Duration & rhs);
|
operator-=(const rclcpp::Duration & rhs);
|
||||||
|
|
||||||
|
/// Get the nanoseconds since epoch
|
||||||
|
/**
|
||||||
|
* \return the nanoseconds since epoch as a rcl_time_point_value_t structure.
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
rcl_time_point_value_t
|
rcl_time_point_value_t
|
||||||
nanoseconds() const;
|
nanoseconds() const;
|
||||||
|
|
||||||
|
/// Get the maximum representable value.
|
||||||
|
/**
|
||||||
|
* \return the maximum representable value
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
static Time
|
static Time
|
||||||
max();
|
max();
|
||||||
|
|
||||||
/// \return the seconds since epoch as a floating point number.
|
/// Get the seconds since epoch
|
||||||
/// \warning Depending on sizeof(double) there could be significant precision loss.
|
/**
|
||||||
/// When an exact time is required use nanoseconds() instead.
|
* \warning Depending on sizeof(double) there could be significant precision loss.
|
||||||
|
* When an exact time is required use nanoseconds() instead.
|
||||||
|
*
|
||||||
|
* \return the seconds since epoch as a floating point number.
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
double
|
double
|
||||||
seconds() const;
|
seconds() const;
|
||||||
|
|
||||||
|
/// Get the clock type
|
||||||
|
/**
|
||||||
|
* \return the clock type
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
rcl_clock_type_t
|
rcl_clock_type_t
|
||||||
get_clock_type() const;
|
get_clock_type() const;
|
||||||
|
|
|
@ -35,15 +35,42 @@ class Clock;
|
||||||
class TimeSource
|
class TimeSource
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
/// Constructor
|
||||||
|
/**
|
||||||
|
* The node will be attached to the time source.
|
||||||
|
*
|
||||||
|
* \param node std::shared pointer to a initialized node
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
explicit TimeSource(rclcpp::Node::SharedPtr node);
|
explicit TimeSource(rclcpp::Node::SharedPtr node);
|
||||||
|
|
||||||
|
/// Empty constructor
|
||||||
|
/**
|
||||||
|
* An Empty TimeSource class
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
TimeSource();
|
TimeSource();
|
||||||
|
|
||||||
|
/// Attack node to the time source.
|
||||||
|
/**
|
||||||
|
* \param node std::shared pointer to a initialized node
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
void attachNode(rclcpp::Node::SharedPtr node);
|
void attachNode(rclcpp::Node::SharedPtr node);
|
||||||
|
|
||||||
|
/// Attack node to the time source.
|
||||||
|
/**
|
||||||
|
* If the parameter `use_sim_time` is `true` then the source time is the simulation time,
|
||||||
|
* otherwise the source time is defined by the system.
|
||||||
|
*
|
||||||
|
* \param node_base_interface Node base interface.
|
||||||
|
* \param node_topics_interface Node topic base interface.
|
||||||
|
* \param node_graph_interface Node graph interface.
|
||||||
|
* \param node_services_interface Node service interface.
|
||||||
|
* \param node_logging_interface Node logging interface.
|
||||||
|
* \param node_clock_interface Node clock interface.
|
||||||
|
* \param node_parameters_interface Node parameters interface.
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
void attachNode(
|
void attachNode(
|
||||||
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
|
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
|
||||||
|
@ -54,19 +81,22 @@ public:
|
||||||
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
|
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
|
||||||
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface);
|
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface);
|
||||||
|
|
||||||
|
/// Detach the node from the time source
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
void detachNode();
|
void detachNode();
|
||||||
|
|
||||||
/// Attach a clock to the time source to be updated
|
/// Attach a clock to the time source to be updated
|
||||||
/**
|
/**
|
||||||
* \throws std::invalid_argument if node is nullptr
|
* \throws std::invalid_argument the time source must be a RCL_ROS_TIME otherwise throws an exception
|
||||||
*/
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
void attachClock(rclcpp::Clock::SharedPtr clock);
|
void attachClock(rclcpp::Clock::SharedPtr clock);
|
||||||
|
|
||||||
|
/// Detach a clock to the time source
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
void detachClock(rclcpp::Clock::SharedPtr clock);
|
void detachClock(rclcpp::Clock::SharedPtr clock);
|
||||||
|
|
||||||
|
/// TimeSource Destructor
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
~TimeSource();
|
~TimeSource();
|
||||||
|
|
||||||
|
|
|
@ -48,15 +48,26 @@ class TimerBase
|
||||||
public:
|
public:
|
||||||
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(TimerBase)
|
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(TimerBase)
|
||||||
|
|
||||||
|
/// TimerBase constructor
|
||||||
|
/**
|
||||||
|
* \param clock A clock to use for time and sleeping
|
||||||
|
* \param period The interval at which the timer fires
|
||||||
|
* \param context node context
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
explicit TimerBase(
|
explicit TimerBase(
|
||||||
Clock::SharedPtr clock,
|
Clock::SharedPtr clock,
|
||||||
std::chrono::nanoseconds period,
|
std::chrono::nanoseconds period,
|
||||||
rclcpp::Context::SharedPtr context);
|
rclcpp::Context::SharedPtr context);
|
||||||
|
|
||||||
|
/// TimerBase destructor
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
~TimerBase();
|
~TimerBase();
|
||||||
|
|
||||||
|
/// Cancel the timer.
|
||||||
|
/**
|
||||||
|
* \throws std::runtime_error if the rcl_timer_cancel returns a failure
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
void
|
void
|
||||||
cancel();
|
cancel();
|
||||||
|
@ -71,10 +82,15 @@ public:
|
||||||
bool
|
bool
|
||||||
is_canceled();
|
is_canceled();
|
||||||
|
|
||||||
|
/// Reset the timer.
|
||||||
|
/**
|
||||||
|
* \throws std::runtime_error if the rcl_timer_reset returns a failure
|
||||||
|
*/
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
void
|
void
|
||||||
reset();
|
reset();
|
||||||
|
|
||||||
|
/// Call the callback function when the timer signal is emitted.
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
virtual void
|
virtual void
|
||||||
execute_callback() = 0;
|
execute_callback() = 0;
|
||||||
|
@ -209,6 +225,8 @@ public:
|
||||||
callback_(*this);
|
callback_(*this);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/// Is the clock steady (i.e. is the time between ticks constant?)
|
||||||
|
/** \return True if the clock used by this timer is steady. */
|
||||||
bool
|
bool
|
||||||
is_steady() override
|
is_steady() override
|
||||||
{
|
{
|
||||||
|
@ -233,6 +251,12 @@ class WallTimer : public GenericTimer<FunctorT>
|
||||||
public:
|
public:
|
||||||
RCLCPP_SMART_PTR_DEFINITIONS(WallTimer)
|
RCLCPP_SMART_PTR_DEFINITIONS(WallTimer)
|
||||||
|
|
||||||
|
/// Wall timer constructor
|
||||||
|
/**
|
||||||
|
* \param period The interval at which the timer fires
|
||||||
|
* \param callback The callback function to execute every interval
|
||||||
|
* \param context node context
|
||||||
|
*/
|
||||||
WallTimer(
|
WallTimer(
|
||||||
std::chrono::nanoseconds period,
|
std::chrono::nanoseconds period,
|
||||||
FunctorT && callback,
|
FunctorT && callback,
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue