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

Fix rclcpp documentation build #1779

Merged
merged 9 commits into from
Jan 7, 2022
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
11 changes: 10 additions & 1 deletion rclcpp/Doxyfile
Original file line number Diff line number Diff line change
Expand Up @@ -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/"
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ class Context : public std::enable_shared_from_this<Context>
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.
Expand Down
18 changes: 16 additions & 2 deletions rclcpp/include/rclcpp/detail/qos_parameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,7 @@ declare_parameter_or_get(
}
}

#ifdef DOXYGEN_ONLY
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

My initial thinking is that this was overkill, and we could use a combination of \fn and \cond/\endcond to do this with a lot less duplication.

But it turns out that that does not work, since you can't use \fn for a function that Doxygen hasn't parsed. That seems like a weakness of Doxygen; having an escape hatch like that would make it so you could always just use Doxygen comments to get around problems in the parser. But I digress.

Since I don't currently see a better way to do this, I'm OK with this workaround. I'd definitely want to have a comment here explaining why we are doing this in the couple of places that we are doing it. Also pinging @wjwwood and @ivanpauno to get opinions.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

But it turns out that that does not work, since you can't use \fn for a function that Doxygen hasn't parsed.

Indeed. I ran into the same issue.

I'd definitely want to have a comment here explaining why we are doing this in the couple of places that we are doing it.

👍

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If there's no other solution, I think this is fine.
I would rather use a documentation generator that supports SFINAE normally, but if that's not an option this seems okay.

/// \internal Declare QoS parameters for the given entity.
/**
* \tparam NodeT Node pointer or reference type.
Expand All @@ -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<typename NodeT, typename EntityQosParametersTraits>
rclcpp::QoS
declare_qos_parameters(
const ::rclcpp::QosOverridingOptions & options,
NodeT & node,
const std::string & topic_name,
const ::rclcpp::QoS & default_qos,
EntityQosParametersTraits);

#else

template<typename NodeT, typename EntityQosParametersTraits>
std::enable_if_t<
rclcpp::node_interfaces::has_node_parameters_interface<
(rclcpp::node_interfaces::has_node_parameters_interface<
decltype(std::declval<typename rcpputils::remove_pointer<NodeT>::type>())>::value ||
std::is_same<typename std::decay_t<NodeT>,
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value,
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr>::value),
rclcpp::QoS>
declare_qos_parameters(
const ::rclcpp::QosOverridingOptions & options,
Expand Down Expand Up @@ -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) \
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ namespace detail
*
* This issue, with the lambda's, can be demonstrated with this minimal program:
*
* \code{.cpp}
* #include <functional>
* #include <memory>
*
Expand All @@ -52,6 +53,7 @@ namespace detail
* std::function<void (std::shared_ptr<int>)> cb = [](std::shared_ptr<int>){};
* f(cb);
* }
* \endcode
*
* If this program ever starts working in a future version of C++, this class
* may become redundant.
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/detail/utilities.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ namespace detail

std::vector<std::string>
get_unparsed_ros_arguments(
int argc, char const * const argv[],
int argc, char const * const * argv,
rcl_arguments_t * arguments,
rcl_allocator_t allocator);

Expand Down
5 changes: 3 additions & 2 deletions rclcpp/include/rclcpp/exceptions/exceptions.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -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")
Expand Down
1 change: 1 addition & 0 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
12 changes: 9 additions & 3 deletions rclcpp/include/rclcpp/function_traits.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,9 @@ struct function_traits<ReturnTypeT (*)(Args ...)>: function_traits<ReturnTypeT(A

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

// std::bind for object const methods
template<typename ClassT, typename ReturnTypeT, typename ... Args, typename ... FArgs>
#if defined _LIBCPP_VERSION // libc++ (Clang)
#if defined DOXYGEN_ONLY
struct function_traits<std::bind<ReturnTypeT (ClassT::*)(Args ...) const, FArgs ...>>
#elif defined _LIBCPP_VERSION // libc++ (Clang)
struct function_traits<std::__bind<ReturnTypeT (ClassT::*)(Args ...) const, FArgs ...>>
#elif defined _GLIBCXX_RELEASE // glibc++ (GNU C++ >= 7.1)
struct function_traits<std::_Bind<ReturnTypeT(ClassT::* (FArgs ...))(Args ...) const>>
Expand All @@ -114,7 +118,9 @@ struct function_traits<

// std::bind for free functions
template<typename ReturnTypeT, typename ... Args, typename ... FArgs>
#if defined _LIBCPP_VERSION // libc++ (Clang)
#if defined DOXYGEN_ONLY
struct function_traits<std::bind<ReturnTypeT( &)(Args ...), FArgs ...>>
#elif defined _LIBCPP_VERSION // libc++ (Clang)
struct function_traits<std::__bind<ReturnTypeT( &)(Args ...), FArgs ...>>
#elif defined __GLIBCXX__ // glibc++ (GNU C++)
struct function_traits<std::_Bind<ReturnTypeT(*(FArgs ...))(Args ...)>>
Expand Down
1 change: 0 additions & 1 deletion rclcpp/include/rclcpp/generic_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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`.
Expand Down
24 changes: 16 additions & 8 deletions rclcpp/include/rclcpp/get_message_type_support_handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<typename MessageT>
constexpr const rosidl_message_type_support_t & get_message_type_support_handle();

#else

template<typename MessageT>
constexpr
typename std::enable_if_t<
Expand All @@ -44,7 +54,6 @@ get_message_type_support_handle()
return *handle;
}

/// Specialization for when MessageT is an adapted type using rclcpp::TypeAdapter.
template<typename AdaptedType>
constexpr
typename std::enable_if_t<
Expand All @@ -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
>
Expand All @@ -85,6 +91,8 @@ get_message_type_support_handle()
"should never be called");
}

#endif

} // namespace rclcpp

#endif // RCLCPP__GET_MESSAGE_TYPE_SUPPORT_HANDLE_HPP_
2 changes: 2 additions & 0 deletions rclcpp/include/rclcpp/guard_condition.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
*/
Expand Down
2 changes: 2 additions & 0 deletions rclcpp/include/rclcpp/time_source.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand All @@ -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(
Expand Down
13 changes: 8 additions & 5 deletions rclcpp/include/rclcpp/utilities.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand 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
Expand Down Expand Up @@ -136,7 +139,7 @@ RCLCPP_PUBLIC
std::vector<std::string>
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.
Expand All @@ -154,7 +157,7 @@ init_and_remove_ros_arguments(
*/
RCLCPP_PUBLIC
std::vector<std::string>
remove_ros_arguments(int argc, char const * const argv[]);
remove_ros_arguments(int argc, char const * const * argv);

/// Check rclcpp's status.
/**
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::recursive_mutex> init_lock(init_mutex_);
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/detail/utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ namespace detail

std::vector<std::string>
get_unparsed_ros_arguments(
int argc, char const * const argv[],
int argc, char const * const * argv,
rcl_arguments_t * arguments,
rcl_allocator_t allocator)
{
Expand Down
8 changes: 4 additions & 4 deletions rclcpp/src/rclcpp/utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down Expand Up @@ -71,7 +71,7 @@ uninstall_signal_handlers()
static
std::vector<std::string>
_remove_ros_arguments(
char const * const argv[],
char const * const * argv,
const rcl_arguments_t * args,
rcl_allocator_t alloc)
{
Expand Down Expand Up @@ -112,7 +112,7 @@ _remove_ros_arguments(
std::vector<std::string>
init_and_remove_ros_arguments(
int argc,
char const * const argv[],
char const * const * argv,
const InitOptions & init_options)
{
init(argc, argv, init_options);
Expand All @@ -123,7 +123,7 @@ init_and_remove_ros_arguments(
}

std::vector<std::string>
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();
Expand Down