Skip to content

Commit 8093648

Browse files
authored
Fix rclcpp documentation build (#1779)
* Update Doxyfile * Update docblocks with warnings * Use leading * instead of trailing [] for pointer types * Help Doxygen parse std::enable_if<> condition * Add documentation-only SFINAE functions' declarations * Avoid function pointer type syntax in function arguments. * Add documentation-only SFINAE function traits. Signed-off-by: Chris Lalancette <[email protected]> Signed-off-by: Michel Hidalgo <[email protected]>
1 parent 9583ec7 commit 8093648

20 files changed

+85
-32
lines changed

rclcpp/Doxyfile

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,16 @@ GENERATE_LATEX = NO
2121
ENABLE_PREPROCESSING = YES
2222
MACRO_EXPANSION = YES
2323
EXPAND_ONLY_PREDEF = YES
24-
PREDEFINED = RCLCPP_PUBLIC=
24+
PREDEFINED += DOXYGEN_ONLY
25+
PREDEFINED += RCLCPP_LOCAL=
26+
PREDEFINED += RCLCPP_PUBLIC=
27+
PREDEFINED += RCLCPP_PUBLIC_TYPE=
28+
PREDEFINED += RCUTILS_WARN_UNUSED=
29+
PREDEFINED += RCPPUTILS_TSA_GUARDED_BY(x)=
30+
PREDEFINED += RCPPUTILS_TSA_PT_GUARDED_BY(x)=
31+
PREDEFINED += RCPPUTILS_TSA_REQUIRES(x)=
32+
33+
DOT_GRAPH_MAX_NODES = 101
2534

2635
# Tag files that do not exist will produce a warning and cross-project linking will not work.
2736
TAGFILES += "../../../../doxygen_tag_files/cppreference-doxygen-web.tag.xml=http://en.cppreference.com/w/"

rclcpp/include/rclcpp/context.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -127,7 +127,7 @@ class Context : public std::enable_shared_from_this<Context>
127127
void
128128
init(
129129
int argc,
130-
char const * const argv[],
130+
char const * const * argv,
131131
const rclcpp::InitOptions & init_options = rclcpp::InitOptions());
132132

133133
/// Return true if the context is valid, otherwise false.

rclcpp/include/rclcpp/detail/qos_parameters.hpp

Lines changed: 16 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -104,6 +104,7 @@ declare_parameter_or_get(
104104
}
105105
}
106106

107+
#ifdef DOXYGEN_ONLY
107108
/// \internal Declare QoS parameters for the given entity.
108109
/**
109110
* \tparam NodeT Node pointer or reference type.
@@ -116,12 +117,23 @@ declare_parameter_or_get(
116117
* \param default_qos User provided qos. It will be used as a default for the parameters declared.
117118
* \return qos profile based on the user provided parameter overrides.
118119
*/
120+
template<typename NodeT, typename EntityQosParametersTraits>
121+
rclcpp::QoS
122+
declare_qos_parameters(
123+
const ::rclcpp::QosOverridingOptions & options,
124+
NodeT & node,
125+
const std::string & topic_name,
126+
const ::rclcpp::QoS & default_qos,
127+
EntityQosParametersTraits);
128+
129+
#else
130+
119131
template<typename NodeT, typename EntityQosParametersTraits>
120132
std::enable_if_t<
121-
rclcpp::node_interfaces::has_node_parameters_interface<
133+
(rclcpp::node_interfaces::has_node_parameters_interface<
122134
decltype(std::declval<typename rcpputils::remove_pointer<NodeT>::type>())>::value ||
123135
std::is_same<typename std::decay_t<NodeT>,
124-
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value,
136+
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value),
125137
rclcpp::QoS>
126138
declare_qos_parameters(
127139
const ::rclcpp::QosOverridingOptions & options,
@@ -204,6 +216,8 @@ declare_qos_parameters(
204216
return default_qos;
205217
}
206218

219+
#endif
220+
207221
/// \internal Helper function to get a rmw qos policy value from a string.
208222
#define RCLCPP_DETAIL_APPLY_QOS_OVERRIDE_FROM_PARAMETER_STRING( \
209223
kind_lower, kind_upper, parameter_value, rclcpp_qos) \

rclcpp/include/rclcpp/detail/subscription_callback_type_helper.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,7 @@ namespace detail
3838
*
3939
* This issue, with the lambda's, can be demonstrated with this minimal program:
4040
*
41+
* \code{.cpp}
4142
* #include <functional>
4243
* #include <memory>
4344
*
@@ -52,6 +53,7 @@ namespace detail
5253
* std::function<void (std::shared_ptr<int>)> cb = [](std::shared_ptr<int>){};
5354
* f(cb);
5455
* }
56+
* \endcode
5557
*
5658
* If this program ever starts working in a future version of C++, this class
5759
* may become redundant.

rclcpp/include/rclcpp/detail/utilities.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ namespace detail
3030

3131
std::vector<std::string>
3232
get_unparsed_ros_arguments(
33-
int argc, char const * const argv[],
33+
int argc, char const * const * argv,
3434
rcl_arguments_t * arguments,
3535
rcl_allocator_t allocator);
3636

rclcpp/include/rclcpp/exceptions/exceptions.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -109,6 +109,8 @@ class UnimplementedError : public std::runtime_error
109109
: std::runtime_error(msg) {}
110110
};
111111

112+
typedef void (* reset_error_function_t)();
113+
112114
/// Throw a C++ std::exception which was created based on an rcl error.
113115
/**
114116
* Passing nullptr for reset_error is safe and will avoid calling any function
@@ -129,7 +131,7 @@ throw_from_rcl_error [[noreturn]] (
129131
rcl_ret_t ret,
130132
const std::string & prefix = "",
131133
const rcl_error_state_t * error_state = nullptr,
132-
void (* reset_error)() = rcl_reset_error);
134+
reset_error_function_t reset_error = rcl_reset_error);
133135
/* *INDENT-ON* */
134136

135137
class RCLErrorBase
@@ -306,7 +308,6 @@ class ParameterUninitializedException : public std::runtime_error
306308
/// Construct an instance.
307309
/**
308310
* \param[in] name the name of the parameter.
309-
* \param[in] message custom exception message.
310311
*/
311312
explicit ParameterUninitializedException(const std::string & name)
312313
: std::runtime_error("parameter '" + name + "' is not initialized")

rclcpp/include/rclcpp/executor.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -455,6 +455,7 @@ class Executor
455455
/// Return true if the node has been added to this executor.
456456
/**
457457
* \param[in] node_ptr a shared pointer that points to a node base interface
458+
* \param[in] weak_groups_to_nodes map to nodes to lookup
458459
* \return true if the node is associated with the executor, otherwise false
459460
*/
460461
RCLCPP_PUBLIC

rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -299,7 +299,8 @@ class StaticExecutorEntitiesCollector final
299299

300300
/// Return true if the node belongs to the collector
301301
/**
302-
* \param[in] group_ptr a node base interface shared pointer
302+
* \param[in] node_ptr a node base interface shared pointer
303+
* \param[in] weak_groups_to_nodes map to nodes to lookup
303304
* \return boolean whether a node belongs the collector
304305
*/
305306
bool

rclcpp/include/rclcpp/experimental/intra_process_manager.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -173,6 +173,7 @@ class IntraProcessManager
173173
*
174174
* \param intra_process_publisher_id the id of the publisher of this message.
175175
* \param message the message that is being stored.
176+
* \param allocator for allocations when buffering messages.
176177
*/
177178
template<
178179
typename MessageT,

rclcpp/include/rclcpp/function_traits.hpp

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,9 @@ struct function_traits<ReturnTypeT (*)(Args ...)>: function_traits<ReturnTypeT(A
8080

8181
// std::bind for object methods
8282
template<typename ClassT, typename ReturnTypeT, typename ... Args, typename ... FArgs>
83-
#if defined _LIBCPP_VERSION // libc++ (Clang)
83+
#if defined DOXYGEN_ONLY
84+
struct function_traits<std::bind<ReturnTypeT (ClassT::*)(Args ...), FArgs ...>>
85+
#elif defined _LIBCPP_VERSION // libc++ (Clang)
8486
struct function_traits<std::__bind<ReturnTypeT (ClassT::*)(Args ...), FArgs ...>>
8587
#elif defined _GLIBCXX_RELEASE // glibc++ (GNU C++ >= 7.1)
8688
struct function_traits<std::_Bind<ReturnTypeT(ClassT::* (FArgs ...))(Args ...)>>
@@ -97,7 +99,9 @@ struct function_traits<
9799

98100
// std::bind for object const methods
99101
template<typename ClassT, typename ReturnTypeT, typename ... Args, typename ... FArgs>
100-
#if defined _LIBCPP_VERSION // libc++ (Clang)
102+
#if defined DOXYGEN_ONLY
103+
struct function_traits<std::bind<ReturnTypeT (ClassT::*)(Args ...) const, FArgs ...>>
104+
#elif defined _LIBCPP_VERSION // libc++ (Clang)
101105
struct function_traits<std::__bind<ReturnTypeT (ClassT::*)(Args ...) const, FArgs ...>>
102106
#elif defined _GLIBCXX_RELEASE // glibc++ (GNU C++ >= 7.1)
103107
struct function_traits<std::_Bind<ReturnTypeT(ClassT::* (FArgs ...))(Args ...) const>>
@@ -114,7 +118,9 @@ struct function_traits<
114118

115119
// std::bind for free functions
116120
template<typename ReturnTypeT, typename ... Args, typename ... FArgs>
117-
#if defined _LIBCPP_VERSION // libc++ (Clang)
121+
#if defined DOXYGEN_ONLY
122+
struct function_traits<std::bind<ReturnTypeT( &)(Args ...), FArgs ...>>
123+
#elif defined _LIBCPP_VERSION // libc++ (Clang)
118124
struct function_traits<std::__bind<ReturnTypeT( &)(Args ...), FArgs ...>>
119125
#elif defined __GLIBCXX__ // glibc++ (GNU C++)
120126
struct function_traits<std::_Bind<ReturnTypeT(*(FArgs ...))(Args ...)>>

0 commit comments

Comments
 (0)