diff --git a/rclcpp/Doxyfile b/rclcpp/Doxyfile index 2a7846b1f8..01541e33d0 100644 --- a/rclcpp/Doxyfile +++ b/rclcpp/Doxyfile @@ -21,7 +21,16 @@ GENERATE_LATEX = NO ENABLE_PREPROCESSING = YES MACRO_EXPANSION = YES EXPAND_ONLY_PREDEF = YES -PREDEFINED = RCLCPP_PUBLIC= +PREDEFINED += DOXYGEN_ONLY +PREDEFINED += RCLCPP_LOCAL= +PREDEFINED += RCLCPP_PUBLIC= +PREDEFINED += RCLCPP_PUBLIC_TYPE= +PREDEFINED += RCUTILS_WARN_UNUSED= +PREDEFINED += RCPPUTILS_TSA_GUARDED_BY(x)= +PREDEFINED += RCPPUTILS_TSA_PT_GUARDED_BY(x)= +PREDEFINED += RCPPUTILS_TSA_REQUIRES(x)= + +DOT_GRAPH_MAX_NODES = 101 # Tag files that do not exist will produce a warning and cross-project linking will not work. TAGFILES += "../../../../doxygen_tag_files/cppreference-doxygen-web.tag.xml=http://en.cppreference.com/w/" diff --git a/rclcpp/include/rclcpp/context.hpp b/rclcpp/include/rclcpp/context.hpp index 227fc3928c..2d8db29d21 100644 --- a/rclcpp/include/rclcpp/context.hpp +++ b/rclcpp/include/rclcpp/context.hpp @@ -127,7 +127,7 @@ class Context : public std::enable_shared_from_this void init( int argc, - char const * const argv[], + char const * const * argv, const rclcpp::InitOptions & init_options = rclcpp::InitOptions()); /// Return true if the context is valid, otherwise false. diff --git a/rclcpp/include/rclcpp/detail/qos_parameters.hpp b/rclcpp/include/rclcpp/detail/qos_parameters.hpp index cd8d9ffef7..651e58e7d2 100644 --- a/rclcpp/include/rclcpp/detail/qos_parameters.hpp +++ b/rclcpp/include/rclcpp/detail/qos_parameters.hpp @@ -104,6 +104,7 @@ declare_parameter_or_get( } } +#ifdef DOXYGEN_ONLY /// \internal Declare QoS parameters for the given entity. /** * \tparam NodeT Node pointer or reference type. @@ -116,12 +117,23 @@ declare_parameter_or_get( * \param default_qos User provided qos. It will be used as a default for the parameters declared. * \return qos profile based on the user provided parameter overrides. */ +template +rclcpp::QoS + declare_qos_parameters( + const ::rclcpp::QosOverridingOptions & options, + NodeT & node, + const std::string & topic_name, + const ::rclcpp::QoS & default_qos, + EntityQosParametersTraits); + +#else + template std::enable_if_t< - rclcpp::node_interfaces::has_node_parameters_interface< + (rclcpp::node_interfaces::has_node_parameters_interface< decltype(std::declval::type>())>::value || std::is_same, - rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value, + rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value), rclcpp::QoS> declare_qos_parameters( const ::rclcpp::QosOverridingOptions & options, @@ -204,6 +216,8 @@ declare_qos_parameters( return default_qos; } +#endif + /// \internal Helper function to get a rmw qos policy value from a string. #define RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING( \ kind_lower, kind_upper, parameter_value, rclcpp_qos) \ diff --git a/rclcpp/include/rclcpp/detail/subscription_callback_type_helper.hpp b/rclcpp/include/rclcpp/detail/subscription_callback_type_helper.hpp index ec24038d79..0ebe6efd66 100644 --- a/rclcpp/include/rclcpp/detail/subscription_callback_type_helper.hpp +++ b/rclcpp/include/rclcpp/detail/subscription_callback_type_helper.hpp @@ -38,6 +38,7 @@ namespace detail * * This issue, with the lambda's, can be demonstrated with this minimal program: * + * \code{.cpp} * #include * #include * @@ -52,6 +53,7 @@ namespace detail * std::function)> cb = [](std::shared_ptr){}; * f(cb); * } + * \endcode * * If this program ever starts working in a future version of C++, this class * may become redundant. diff --git a/rclcpp/include/rclcpp/detail/utilities.hpp b/rclcpp/include/rclcpp/detail/utilities.hpp index 62012ba0c8..d1c5d2549a 100644 --- a/rclcpp/include/rclcpp/detail/utilities.hpp +++ b/rclcpp/include/rclcpp/detail/utilities.hpp @@ -30,7 +30,7 @@ namespace detail std::vector get_unparsed_ros_arguments( - int argc, char const * const argv[], + int argc, char const * const * argv, rcl_arguments_t * arguments, rcl_allocator_t allocator); diff --git a/rclcpp/include/rclcpp/exceptions/exceptions.hpp b/rclcpp/include/rclcpp/exceptions/exceptions.hpp index 524ccf73ea..51f2a5edce 100644 --- a/rclcpp/include/rclcpp/exceptions/exceptions.hpp +++ b/rclcpp/include/rclcpp/exceptions/exceptions.hpp @@ -109,6 +109,8 @@ class UnimplementedError : public std::runtime_error : std::runtime_error(msg) {} }; +typedef void (* reset_error_function_t)(); + /// Throw a C++ std::exception which was created based on an rcl error. /** * Passing nullptr for reset_error is safe and will avoid calling any function @@ -129,7 +131,7 @@ throw_from_rcl_error [[noreturn]] ( rcl_ret_t ret, const std::string & prefix = "", const rcl_error_state_t * error_state = nullptr, - void (* reset_error)() = rcl_reset_error); + reset_error_function_t reset_error = rcl_reset_error); /* *INDENT-ON* */ class RCLErrorBase @@ -289,7 +291,6 @@ class ParameterUninitializedException : public std::runtime_error /// Construct an instance. /** * \param[in] name the name of the parameter. - * \param[in] message custom exception message. */ explicit ParameterUninitializedException(const std::string & name) : std::runtime_error("parameter '" + name + "' is not initialized") diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index dfd88ccea2..77d6a5f447 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -455,6 +455,7 @@ class Executor /// Return true if the node has been added to this executor. /** * \param[in] node_ptr a shared pointer that points to a node base interface + * \param[in] weak_groups_to_nodes map to nodes to lookup * \return true if the node is associated with the executor, otherwise false */ RCLCPP_PUBLIC diff --git a/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp b/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp index bda28cb74b..f9fd2ff672 100644 --- a/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp +++ b/rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp @@ -299,7 +299,8 @@ class StaticExecutorEntitiesCollector final /// Return true if the node belongs to the collector /** - * \param[in] group_ptr a node base interface shared pointer + * \param[in] node_ptr a node base interface shared pointer + * \param[in] weak_groups_to_nodes map to nodes to lookup * \return boolean whether a node belongs the collector */ bool diff --git a/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp b/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp index a927a81856..16c6039b76 100644 --- a/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp +++ b/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp @@ -173,6 +173,7 @@ class IntraProcessManager * * \param intra_process_publisher_id the id of the publisher of this message. * \param message the message that is being stored. + * \param allocator for allocations when buffering messages. */ template< typename MessageT, diff --git a/rclcpp/include/rclcpp/function_traits.hpp b/rclcpp/include/rclcpp/function_traits.hpp index 4dd3cc28db..b6af0aeb47 100644 --- a/rclcpp/include/rclcpp/function_traits.hpp +++ b/rclcpp/include/rclcpp/function_traits.hpp @@ -80,7 +80,9 @@ struct function_traits: function_traits -#if defined _LIBCPP_VERSION // libc++ (Clang) +#if defined DOXYGEN_ONLY +struct function_traits> +#elif defined _LIBCPP_VERSION // libc++ (Clang) struct function_traits> #elif defined _GLIBCXX_RELEASE // glibc++ (GNU C++ >= 7.1) struct function_traits> @@ -97,7 +99,9 @@ struct function_traits< // std::bind for object const methods template -#if defined _LIBCPP_VERSION // libc++ (Clang) +#if defined DOXYGEN_ONLY +struct function_traits> +#elif defined _LIBCPP_VERSION // libc++ (Clang) struct function_traits> #elif defined _GLIBCXX_RELEASE // glibc++ (GNU C++ >= 7.1) struct function_traits> @@ -114,7 +118,9 @@ struct function_traits< // std::bind for free functions template -#if defined _LIBCPP_VERSION // libc++ (Clang) +#if defined DOXYGEN_ONLY +struct function_traits> +#elif defined _LIBCPP_VERSION // libc++ (Clang) struct function_traits> #elif defined __GLIBCXX__ // glibc++ (GNU C++) struct function_traits> diff --git a/rclcpp/include/rclcpp/generic_publisher.hpp b/rclcpp/include/rclcpp/generic_publisher.hpp index 7cadda5d1d..e379f09427 100644 --- a/rclcpp/include/rclcpp/generic_publisher.hpp +++ b/rclcpp/include/rclcpp/generic_publisher.hpp @@ -60,7 +60,6 @@ class GenericPublisher : public rclcpp::PublisherBase * \param topic_name Topic name * \param topic_type Topic type * \param qos %QoS settings - * \param callback Callback for new messages of serialized form * \param options %Publisher options. * Not all publisher options are currently respected, the only relevant options for this * publisher are `event_callbacks`, `use_default_callbacks`, and `%callback_group`. diff --git a/rclcpp/include/rclcpp/get_message_type_support_handle.hpp b/rclcpp/include/rclcpp/get_message_type_support_handle.hpp index 2f19528baf..cbc2e6035b 100644 --- a/rclcpp/include/rclcpp/get_message_type_support_handle.hpp +++ b/rclcpp/include/rclcpp/get_message_type_support_handle.hpp @@ -28,7 +28,17 @@ namespace rclcpp { -/// Specialization for when MessageT is an actual ROS message type. +#ifdef DOXYGEN_ONLY + +/// Returns the message type support for the given `MessageT` type. +/** + * \tparam MessageT an actual ROS message type or an adapted type using `rclcpp::TypeAdapter` + */ +template +constexpr const rosidl_message_type_support_t & get_message_type_support_handle(); + +#else + template constexpr typename std::enable_if_t< @@ -44,7 +54,6 @@ get_message_type_support_handle() return *handle; } -/// Specialization for when MessageT is an adapted type using rclcpp::TypeAdapter. template constexpr typename std::enable_if_t< @@ -63,12 +72,9 @@ get_message_type_support_handle() return *handle; } -/// Specialization for when MessageT is not a ROS message nor an adapted type. -/** - * This specialization is a pass through runtime check, which allows a better - * static_assert to catch this issue further down the line. - * This should never get to be called in practice, and is purely defensive. - */ +// This specialization is a pass through runtime check, which allows a better +// static_assert to catch this issue further down the line. +// This should never get to be called in practice, and is purely defensive. template< typename AdaptedType > @@ -85,6 +91,8 @@ get_message_type_support_handle() "should never be called"); } +#endif + } // namespace rclcpp #endif // RCLCPP__GET_MESSAGE_TYPE_SUPPORT_HANDLE_HPP_ diff --git a/rclcpp/include/rclcpp/guard_condition.hpp b/rclcpp/include/rclcpp/guard_condition.hpp index 5104a6446c..fce42f1d4b 100644 --- a/rclcpp/include/rclcpp/guard_condition.hpp +++ b/rclcpp/include/rclcpp/guard_condition.hpp @@ -40,6 +40,8 @@ class GuardCondition * Defaults to using the global default context singleton. * Shared ownership of the context is held with the guard condition until * destruction. + * \param[in] guard_condition_options Optional guard condition options to be used. + * Defaults to using the default guard condition options. * \throws std::invalid_argument if the context is nullptr. * \throws rclcpp::exceptions::RCLError based exceptions when underlying * rcl functions fail. diff --git a/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp index 243c22cf5e..3958f5b2d9 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_graph_interface.hpp @@ -357,6 +357,8 @@ class NodeGraphInterface /// Return the topic endpoint information about publishers on a given topic. /** * \param[in] topic_name the actual topic name used; it will not be automatically remapped. + * \param[in] no_mangle if `true`, `topic_name` needs to be a valid middleware topic name, + * otherwise it should be a valid ROS topic name. * \sa rclcpp::Node::get_publishers_info_by_topic */ RCLCPP_PUBLIC @@ -367,6 +369,8 @@ class NodeGraphInterface /// Return the topic endpoint information about subscriptions on a given topic. /** * \param[in] topic_name the actual topic name used; it will not be automatically remapped. + * \param[in] no_mangle if `true`, `topic_name` needs to be a valid middleware topic name, + * otherwise it should be a valid ROS topic name. * \sa rclcpp::Node::get_subscriptions_info_by_topic */ RCLCPP_PUBLIC diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 4a15a35141..e03d7f519f 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -185,7 +185,7 @@ class AsyncParametersClient /** * This function filters the parameters to be set based on the node name. * - * \param yaml_filename the full name of the yaml file + * \param parameter_map named parameters to be loaded * \return the future of the set_parameter service used to load the parameters * \throw InvalidParametersException if there is no parameter to set */ diff --git a/rclcpp/include/rclcpp/time_source.hpp b/rclcpp/include/rclcpp/time_source.hpp index 9d067d933c..84984da6e4 100644 --- a/rclcpp/include/rclcpp/time_source.hpp +++ b/rclcpp/include/rclcpp/time_source.hpp @@ -56,6 +56,7 @@ class TimeSource * * \param node std::shared pointer to a initialized node * \param qos QoS that will be used when creating a `/clock` subscription. + * \param use_clock_thread whether to spin the attached node in a separate thread */ RCLCPP_PUBLIC explicit TimeSource( @@ -68,6 +69,7 @@ class TimeSource * An Empty TimeSource class * * \param qos QoS that will be used when creating a `/clock` subscription. + * \param use_clock_thread whether to spin the attached node in a separate thread. */ RCLCPP_PUBLIC explicit TimeSource( diff --git a/rclcpp/include/rclcpp/utilities.hpp b/rclcpp/include/rclcpp/utilities.hpp index e9d8408bb3..fa48a010c4 100644 --- a/rclcpp/include/rclcpp/utilities.hpp +++ b/rclcpp/include/rclcpp/utilities.hpp @@ -65,13 +65,16 @@ enum class SignalHandlerOptions * * \sa rclcpp::Context::init() for more details on arguments and possible exceptions * - * \param signal_handler_options option to indicate which signal handlers should be installed. + * \param[in] argc number of command-line arguments to parse. + * \param[in] argv array of command-line arguments to parse. + * \param[in] init_options initialization options to apply. + * \param[in] signal_handler_options option to indicate which signal handlers should be installed. */ RCLCPP_PUBLIC void init( int argc, - char const * const argv[], + char const * const * argv, const InitOptions & init_options = InitOptions(), SignalHandlerOptions signal_handler_options = SignalHandlerOptions::All); @@ -87,7 +90,7 @@ init( * * This function is thread-safe. * - * \param signal_handler_options option to indicate which signal handlers should be installed. + * \param[in] signal_handler_options option to indicate which signal handlers should be installed. * \return true if signal handler was installed by this function, false if already installed. */ RCLCPP_PUBLIC @@ -136,7 +139,7 @@ RCLCPP_PUBLIC std::vector init_and_remove_ros_arguments( int argc, - char const * const argv[], + char const * const * argv, const InitOptions & init_options = InitOptions()); /// Remove ROS-specific arguments from argument vector. @@ -154,7 +157,7 @@ init_and_remove_ros_arguments( */ RCLCPP_PUBLIC std::vector -remove_ros_arguments(int argc, char const * const argv[]); +remove_ros_arguments(int argc, char const * const * argv); /// Check rclcpp's status. /** diff --git a/rclcpp/src/rclcpp/context.cpp b/rclcpp/src/rclcpp/context.cpp index fff5753954..d3d123c065 100644 --- a/rclcpp/src/rclcpp/context.cpp +++ b/rclcpp/src/rclcpp/context.cpp @@ -192,7 +192,7 @@ __delete_context(rcl_context_t * context) void Context::init( int argc, - char const * const argv[], + char const * const * argv, const rclcpp::InitOptions & init_options) { std::lock_guard init_lock(init_mutex_); diff --git a/rclcpp/src/rclcpp/detail/utilities.cpp b/rclcpp/src/rclcpp/detail/utilities.cpp index 179756f6a3..0166f2dceb 100644 --- a/rclcpp/src/rclcpp/detail/utilities.cpp +++ b/rclcpp/src/rclcpp/detail/utilities.cpp @@ -31,7 +31,7 @@ namespace detail std::vector get_unparsed_ros_arguments( - int argc, char const * const argv[], + int argc, char const * const * argv, rcl_arguments_t * arguments, rcl_allocator_t allocator) { diff --git a/rclcpp/src/rclcpp/utilities.cpp b/rclcpp/src/rclcpp/utilities.cpp index dcc79c96b8..a6ead85c03 100644 --- a/rclcpp/src/rclcpp/utilities.cpp +++ b/rclcpp/src/rclcpp/utilities.cpp @@ -33,7 +33,7 @@ namespace rclcpp void init( int argc, - char const * const argv[], + char const * const * argv, const InitOptions & init_options, SignalHandlerOptions signal_handler_options) { @@ -71,7 +71,7 @@ uninstall_signal_handlers() static std::vector _remove_ros_arguments( - char const * const argv[], + char const * const * argv, const rcl_arguments_t * args, rcl_allocator_t alloc) { @@ -112,7 +112,7 @@ _remove_ros_arguments( std::vector init_and_remove_ros_arguments( int argc, - char const * const argv[], + char const * const * argv, const InitOptions & init_options) { init(argc, argv, init_options); @@ -123,7 +123,7 @@ init_and_remove_ros_arguments( } std::vector -remove_ros_arguments(int argc, char const * const argv[]) +remove_ros_arguments(int argc, char const * const * argv) { rcl_allocator_t alloc = rcl_get_default_allocator(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();