Doxygen setup (#293)
* basic doxygen configuration * fix up documentation * change default value of PROJECT_NUMBER * more generalization * fixup * fixup * avoid displaying RCLCPP_PUBLIC on all functions * main page
This commit is contained in:
parent
0515e7aaf2
commit
321e0b61b0
22 changed files with 250 additions and 74 deletions
1
rclcpp/.gitignore
vendored
Normal file
1
rclcpp/.gitignore
vendored
Normal file
|
@ -0,0 +1 @@
|
|||
doc_output
|
27
rclcpp/Doxyfile
Normal file
27
rclcpp/Doxyfile
Normal file
|
@ -0,0 +1,27 @@
|
|||
# All settings not listed here will use the Doxygen default values.
|
||||
|
||||
PROJECT_NAME = "rclcpp"
|
||||
PROJECT_NUMBER = master
|
||||
PROJECT_BRIEF = "C++ ROS Client Library API"
|
||||
|
||||
INPUT = ./include
|
||||
RECURSIVE = YES
|
||||
OUTPUT_DIRECTORY = doc_output
|
||||
|
||||
EXTRACT_ALL = YES
|
||||
SORT_MEMBER_DOCS = NO
|
||||
|
||||
GENERATE_LATEX = NO
|
||||
|
||||
ENABLE_PREPROCESSING = YES
|
||||
MACRO_EXPANSION = YES
|
||||
EXPAND_ONLY_PREDEF = YES
|
||||
PREDEFINED = RCLCPP_PUBLIC=
|
||||
|
||||
# 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/"
|
||||
# Consider changing "latest" to the version you want to reference (e.g. beta1 or 1.0.0)
|
||||
TAGFILES += "../../../../doxygen_tag_files/rcl.tag=http://docs.ros2.org/latest/api/rcl/"
|
||||
TAGFILES += "../../../../doxygen_tag_files/rmw.tag=http://docs.ros2.org/latest/api/rmw/"
|
||||
# Uncomment to generate tag files for cross-project linking.
|
||||
#GENERATE_TAGFILE = "../../../../doxygen_tag_files/rclcpp.tag"
|
|
@ -36,7 +36,7 @@ public:
|
|||
};
|
||||
|
||||
/// Throw a C++ std::exception which was created based on an rcl error.
|
||||
/*
|
||||
/**
|
||||
* \param ret the return code for the current error state
|
||||
* \param prefix string to prefix to the error if applicable (not all errors have custom messages)
|
||||
* \param reset_error if true rcl_reset_error() is called before returning
|
||||
|
|
|
@ -202,14 +202,13 @@ public:
|
|||
|
||||
/// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
|
||||
/**
|
||||
* \param[in] executor The executor which will spin the node.
|
||||
* \param[in] node_ptr The node to spin.
|
||||
* \param[in] future The future to wait on. If SUCCESS, the future is safe to access after this
|
||||
function.
|
||||
* function.
|
||||
* \param[in] timeout Optional timeout parameter, which gets passed to Executor::spin_node_once.
|
||||
-1 is block forever, 0 is non-blocking.
|
||||
If the time spent inside the blocking loop exceeds this timeout, return a TIMEOUT return code.
|
||||
* \return The return code, one of SUCCESS, INTERRUPTED, or TIMEOUT.
|
||||
* `-1` is block forever, `0` is non-blocking.
|
||||
* If the time spent inside the blocking loop exceeds this timeout, return a TIMEOUT return
|
||||
* code.
|
||||
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
|
||||
*/
|
||||
template<typename ResponseT, typename TimeT = std::milli>
|
||||
FutureReturnCode
|
||||
|
|
|
@ -28,7 +28,7 @@ namespace rclcpp
|
|||
{
|
||||
|
||||
/// Create a default single-threaded executor and execute any immediately available work.
|
||||
// \param[in] node_ptr Shared pointer to the node to spin.
|
||||
/** \param[in] node_ptr Shared pointer to the node to spin. */
|
||||
RCLCPP_PUBLIC
|
||||
void
|
||||
spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);
|
||||
|
@ -38,7 +38,7 @@ void
|
|||
spin_some(rclcpp::node::Node::SharedPtr node_ptr);
|
||||
|
||||
/// Create a default single-threaded executor and spin the specified node.
|
||||
// \param[in] node_ptr Shared pointer to the node to spin.
|
||||
/** \param[in] node_ptr Shared pointer to the node to spin. */
|
||||
RCLCPP_PUBLIC
|
||||
void
|
||||
spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);
|
||||
|
@ -57,11 +57,13 @@ using rclcpp::executors::single_threaded_executor::SingleThreadedExecutor;
|
|||
/**
|
||||
* \param[in] executor The executor which will spin the node.
|
||||
* \param[in] node_ptr The node to spin.
|
||||
* \param[in] future The future to wait on. If SUCCESS, the future is safe to access after this function
|
||||
* \param[in] timeout Optional timeout parameter, which gets passed to Executor::spin_node_once.
|
||||
-1 is block forever, 0 is non-blocking.
|
||||
If the time spent inside the blocking loop exceeds this timeout, return a TIMEOUT return code.
|
||||
* \return The return code, one of SUCCESS, INTERRUPTED, or TIMEOUT.
|
||||
* \param[in] future The future to wait on. If `SUCCESS`, the future is safe to
|
||||
* access after this function
|
||||
* \param[in] timeout Optional timeout parameter, which gets passed to
|
||||
* Executor::spin_node_once.
|
||||
* `-1` is block forever, `0` is non-blocking.
|
||||
* If the time spent inside the blocking loop exceeds this timeout, return a `TIMEOUT` return code.
|
||||
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
|
||||
*/
|
||||
template<typename ResponseT, typename TimeT = std::milli>
|
||||
rclcpp::executor::FutureReturnCode
|
||||
|
|
|
@ -68,7 +68,8 @@ public:
|
|||
virtual ~GraphListener();
|
||||
|
||||
/// Start the graph listener's listen thread if it hasn't been started.
|
||||
/* This function is thread-safe.
|
||||
/**
|
||||
* This function is thread-safe.
|
||||
*
|
||||
* \throws GraphListenerShutdownError if the GraphListener is shutdown
|
||||
*/
|
||||
|
@ -78,7 +79,7 @@ public:
|
|||
start_if_not_started();
|
||||
|
||||
/// Add a node to the graph listener's list of nodes.
|
||||
/*
|
||||
/**
|
||||
* \throws GraphListenerShutdownError if the GraphListener is shutdown
|
||||
* \throws NodeAlreadyAddedError if the given node is already in the list
|
||||
* \throws std::invalid_argument if node is nullptr
|
||||
|
@ -90,7 +91,8 @@ public:
|
|||
add_node(rclcpp::node_interfaces::NodeGraphInterface * node_graph);
|
||||
|
||||
/// Return true if the given node is in the graph listener's list of nodes.
|
||||
/* Also return false if given nullptr.
|
||||
/**
|
||||
* Also return false if given nullptr.
|
||||
*
|
||||
* \throws std::system_error anything std::mutex::lock() throws
|
||||
*/
|
||||
|
@ -100,7 +102,8 @@ public:
|
|||
has_node(rclcpp::node_interfaces::NodeGraphInterface * node_graph);
|
||||
|
||||
/// Remove a node from the graph listener's list of nodes.
|
||||
/*
|
||||
/**
|
||||
*
|
||||
* \throws NodeNotFoundError if the given node is not in the list
|
||||
* \throws std::invalid_argument if node is nullptr
|
||||
* \throws std::system_error anything std::mutex::lock() throws
|
||||
|
@ -111,7 +114,8 @@ public:
|
|||
remove_node(rclcpp::node_interfaces::NodeGraphInterface * node_graph);
|
||||
|
||||
/// Stop the listening thread.
|
||||
/* The thread cannot be restarted, and the class is defunct after calling.
|
||||
/**
|
||||
* The thread cannot be restarted, and the class is defunct after calling.
|
||||
* This function is called by the ~GraphListener() and does nothing if
|
||||
* shutdown() was already called.
|
||||
* This function exists separately from the ~GraphListener() so that it can
|
||||
|
|
|
@ -40,7 +40,8 @@ namespace intra_process_manager
|
|||
{
|
||||
|
||||
/// This class facilitates intra process communication between nodes.
|
||||
/* This class is used in the creation of publishers and subscriptions.
|
||||
/**
|
||||
* This class is used in the creation of publishers and subscriptions.
|
||||
* A singleton instance of this class is owned by a rclcpp::Context and a
|
||||
* rclcpp::Node can use an associated Context to get an instance of this class.
|
||||
* Nodes which do not have a common Context will not exchange intra process
|
||||
|
@ -133,7 +134,8 @@ public:
|
|||
virtual ~IntraProcessManager();
|
||||
|
||||
/// Register a subscription with the manager, returns subscriptions unique id.
|
||||
/* In addition to generating a unique intra process id for the subscription,
|
||||
/**
|
||||
* In addition to generating a unique intra process id for the subscription,
|
||||
* this method also stores the topic name of the subscription.
|
||||
*
|
||||
* This method is normally called during the creation of a subscription,
|
||||
|
@ -149,7 +151,8 @@ public:
|
|||
add_subscription(subscription::SubscriptionBase::SharedPtr subscription);
|
||||
|
||||
/// Unregister a subscription using the subscription's unique id.
|
||||
/* This method does not allocate memory.
|
||||
/**
|
||||
* This method does not allocate memory.
|
||||
*
|
||||
* \param intra_process_subscription_id id of the subscription to remove.
|
||||
*/
|
||||
|
@ -158,7 +161,8 @@ public:
|
|||
remove_subscription(uint64_t intra_process_subscription_id);
|
||||
|
||||
/// Register a publisher with the manager, returns the publisher unique id.
|
||||
/* In addition to generating and returning a unique id for the publisher,
|
||||
/**
|
||||
* In addition to generating and returning a unique id for the publisher,
|
||||
* this method creates internal ring buffer storage for "in-flight" intra
|
||||
* process messages which are stored when store_intra_process_message is
|
||||
* called with this publisher's unique id.
|
||||
|
@ -194,7 +198,8 @@ public:
|
|||
}
|
||||
|
||||
/// Unregister a publisher using the publisher's unique id.
|
||||
/* This method does not allocate memory.
|
||||
/**
|
||||
* This method does not allocate memory.
|
||||
*
|
||||
* \param intra_process_publisher_id id of the publisher to remove.
|
||||
*/
|
||||
|
@ -203,7 +208,8 @@ public:
|
|||
remove_publisher(uint64_t intra_process_publisher_id);
|
||||
|
||||
/// Store a message in the manager, and return the message sequence number.
|
||||
/* The given message is stored in internal storage using the given publisher
|
||||
/**
|
||||
* The given message is stored in internal storage using the given publisher
|
||||
* id and the newly generated message sequence, which is also returned.
|
||||
* The combination of publisher id and message sequence number can later
|
||||
* be used with a subscription id to retrieve the message by calling
|
||||
|
@ -261,7 +267,8 @@ public:
|
|||
}
|
||||
|
||||
/// Take an intra process message.
|
||||
/* The intra_process_publisher_id and message_sequence_number parameters
|
||||
/**
|
||||
* The intra_process_publisher_id and message_sequence_number parameters
|
||||
* uniquely identify a message instance, which should be taken.
|
||||
*
|
||||
* The requesting_subscriptions_intra_process_id parameter is used to make
|
||||
|
|
|
@ -18,7 +18,8 @@
|
|||
#ifndef RCLCPP__MACROS_HPP_
|
||||
#define RCLCPP__MACROS_HPP_
|
||||
|
||||
/* Disables the copy constructor and operator= for the given class.
|
||||
/**
|
||||
* Disables the copy constructor and operator= for the given class.
|
||||
*
|
||||
* Use in the private section of the class.
|
||||
*/
|
||||
|
@ -26,38 +27,41 @@
|
|||
__VA_ARGS__(const __VA_ARGS__ &) = delete; \
|
||||
__VA_ARGS__ & operator=(const __VA_ARGS__ &) = delete;
|
||||
|
||||
/* Defines aliases and static functions for using the Class with smart pointers.
|
||||
/**
|
||||
* Defines aliases and static functions for using the Class with smart pointers.
|
||||
*
|
||||
* Use in the public section of the class.
|
||||
* Make sure to include <memory> in the header when using this.
|
||||
* Make sure to include `<memory>` in the header when using this.
|
||||
*/
|
||||
#define RCLCPP_SMART_PTR_DEFINITIONS(...) \
|
||||
RCLCPP_SHARED_PTR_DEFINITIONS(__VA_ARGS__) \
|
||||
RCLCPP_WEAK_PTR_DEFINITIONS(__VA_ARGS__) \
|
||||
RCLCPP_UNIQUE_PTR_DEFINITIONS(__VA_ARGS__)
|
||||
|
||||
/* Defines aliases and static functions for using the Class with smart pointers.
|
||||
/**
|
||||
* Defines aliases and static functions for using the Class with smart pointers.
|
||||
*
|
||||
* Same as RCLCPP_SMART_PTR_DEFINITIONS expect it excludes the static
|
||||
* Class::make_unique() method definition which does not work on classes which
|
||||
* are not CopyConstructable.
|
||||
*
|
||||
* Use in the public section of the class.
|
||||
* Make sure to include <memory> in the header when using this.
|
||||
* Make sure to include `<memory>` in the header when using this.
|
||||
*/
|
||||
#define RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(...) \
|
||||
RCLCPP_SHARED_PTR_DEFINITIONS(__VA_ARGS__) \
|
||||
RCLCPP_WEAK_PTR_DEFINITIONS(__VA_ARGS__) \
|
||||
__RCLCPP_UNIQUE_PTR_ALIAS(__VA_ARGS__)
|
||||
|
||||
/* Defines aliases only for using the Class with smart pointers.
|
||||
/**
|
||||
* Defines aliases only for using the Class with smart pointers.
|
||||
*
|
||||
* Same as RCLCPP_SMART_PTR_DEFINITIONS expect it excludes the static
|
||||
* method definitions which do not work on pure virtual classes and classes
|
||||
* which are not CopyConstructable.
|
||||
*
|
||||
* Use in the public section of the class.
|
||||
* Make sure to include <memory> in the header when using this.
|
||||
* Make sure to include `<memory>` in the header when using this.
|
||||
*/
|
||||
#define RCLCPP_SMART_PTR_ALIASES_ONLY(...) \
|
||||
__RCLCPP_SHARED_PTR_ALIAS(__VA_ARGS__) \
|
||||
|
|
|
@ -39,7 +39,8 @@ public:
|
|||
};
|
||||
|
||||
/// Ring buffer container of unique_ptr's of T, which can be accessed by a key.
|
||||
/* T must be a CopyConstructable and CopyAssignable.
|
||||
/**
|
||||
* T must be a CopyConstructable and CopyAssignable.
|
||||
* This class can be used in a container by using the base class MappedRingBufferBase.
|
||||
* This class must have a positive, non-zero size.
|
||||
* This class cannot be resized nor can it reserve additional space after construction.
|
||||
|
@ -66,9 +67,11 @@ public:
|
|||
using ElemUniquePtr = std::unique_ptr<T, ElemDeleter>;
|
||||
|
||||
/// Constructor.
|
||||
/* The constructor will allocate memory while reserving space.
|
||||
/**
|
||||
* The constructor will allocate memory while reserving space.
|
||||
*
|
||||
* \param size size of the ring buffer; must be positive and non-zero.
|
||||
* \param allocator optional custom allocator
|
||||
*/
|
||||
explicit MappedRingBuffer(size_t size, std::shared_ptr<Alloc> allocator = nullptr)
|
||||
: elements_(size), head_(0)
|
||||
|
@ -86,7 +89,8 @@ public:
|
|||
virtual ~MappedRingBuffer() {}
|
||||
|
||||
/// Return a copy of the value stored in the ring buffer at the given key.
|
||||
/* The key is matched if an element in the ring buffer has a matching key.
|
||||
/**
|
||||
* The key is matched if an element in the ring buffer has a matching key.
|
||||
* This method will allocate in order to return a copy.
|
||||
*
|
||||
* The key is not guaranteed to be unique, see the class docs for more.
|
||||
|
@ -110,7 +114,8 @@ public:
|
|||
}
|
||||
|
||||
/// Return ownership of the value stored in the ring buffer, leaving a copy.
|
||||
/* The key is matched if an element in the ring bufer has a matching key.
|
||||
/**
|
||||
* The key is matched if an element in the ring bufer has a matching key.
|
||||
* This method will allocate in order to store a copy.
|
||||
*
|
||||
* The key is not guaranteed to be unique, see the class docs for more.
|
||||
|
@ -147,7 +152,8 @@ public:
|
|||
}
|
||||
|
||||
/// Return ownership of the value stored in the ring buffer at the given key.
|
||||
/* The key is matched if an element in the ring buffer has a matching key.
|
||||
/**
|
||||
* The key is matched if an element in the ring buffer has a matching key.
|
||||
*
|
||||
* The key is not guaranteed to be unique, see the class docs for more.
|
||||
*
|
||||
|
@ -169,7 +175,8 @@ public:
|
|||
}
|
||||
|
||||
/// Insert a key-value pair, displacing an existing pair if necessary.
|
||||
/* The key's uniqueness is not checked on insertion.
|
||||
/**
|
||||
* The key's uniqueness is not checked on insertion.
|
||||
* It is up to the user to ensure the key is unique.
|
||||
* This method should not allocate memory.
|
||||
*
|
||||
|
|
|
@ -28,7 +28,7 @@ namespace message_memory_strategy
|
|||
{
|
||||
|
||||
/// Default allocation strategy for messages received by subscriptions.
|
||||
// A message memory strategy must be templated on the type of the subscription it belongs to.
|
||||
/** A message memory strategy must be templated on the type of the subscription it belongs to. */
|
||||
template<typename MessageT, typename Alloc = std::allocator<void>>
|
||||
class MessageMemoryStrategy
|
||||
{
|
||||
|
@ -56,14 +56,14 @@ public:
|
|||
}
|
||||
|
||||
/// By default, dynamically allocate a new message.
|
||||
// \return Shared pointer to the new message.
|
||||
/** \return Shared pointer to the new message. */
|
||||
virtual std::shared_ptr<MessageT> borrow_message()
|
||||
{
|
||||
return std::allocate_shared<MessageT, MessageAlloc>(*message_allocator_.get());
|
||||
}
|
||||
|
||||
/// Release ownership of the message, which will deallocate it if it has no more owners.
|
||||
// \param[in] Shared pointer to the message we are returning.
|
||||
/** \param[in] msg Shared pointer to the message we are returning. */
|
||||
virtual void return_message(std::shared_ptr<MessageT> & msg)
|
||||
{
|
||||
msg.reset();
|
||||
|
|
|
@ -89,7 +89,7 @@ public:
|
|||
virtual ~Node();
|
||||
|
||||
/// Get the name of the node.
|
||||
// \return The name of the node.
|
||||
/** \return The name of the node. */
|
||||
RCLCPP_PUBLIC
|
||||
const char *
|
||||
get_name() const;
|
||||
|
@ -108,6 +108,7 @@ public:
|
|||
/**
|
||||
* \param[in] topic_name The topic for this publisher to publish on.
|
||||
* \param[in] qos_history_depth The depth of the publisher message queue.
|
||||
* \param[in] allocator Optional custom allocator.
|
||||
* \return Shared pointer to the created publisher.
|
||||
*/
|
||||
template<
|
||||
|
@ -122,6 +123,7 @@ public:
|
|||
/**
|
||||
* \param[in] topic_name The topic for this publisher to publish on.
|
||||
* \param[in] qos_profile The quality of service profile to pass on to the rmw implementation.
|
||||
* \param[in] allocator Optional custom allocator.
|
||||
* \return Shared pointer to the created publisher.
|
||||
*/
|
||||
template<
|
||||
|
@ -141,6 +143,7 @@ public:
|
|||
* \param[in] group The callback group for this subscription. NULL for no callback group.
|
||||
* \param[in] ignore_local_publications True to ignore local publications.
|
||||
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
|
||||
* \param[in] allocator Optional custom allocator.
|
||||
* \return Shared pointer to the created subscription.
|
||||
*/
|
||||
/* TODO(jacquelinekay):
|
||||
|
@ -171,6 +174,7 @@ public:
|
|||
* \param[in] group The callback group for this subscription. NULL for no callback group.
|
||||
* \param[in] ignore_local_publications True to ignore local publications.
|
||||
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
|
||||
* \param[in] allocator Optional custom allocator.
|
||||
* \return Shared pointer to the created subscription.
|
||||
*/
|
||||
/* TODO(jacquelinekay):
|
||||
|
@ -263,7 +267,8 @@ public:
|
|||
|
||||
/// Register the callback for parameter changes
|
||||
/**
|
||||
* \param[in] User defined callback function, It is expected to atomically set parameters.
|
||||
* \param[in] callback User defined callback function.
|
||||
* It is expected to atomically set parameters.
|
||||
* \note Repeated invocations of this function will overwrite previous callbacks
|
||||
*/
|
||||
template<typename CallbackT>
|
||||
|
@ -292,7 +297,8 @@ public:
|
|||
get_graph_event();
|
||||
|
||||
/// Wait for a graph event to occur by waiting on an Event to become set.
|
||||
/* The given Event must be acquire through the get_graph_event() method.
|
||||
/**
|
||||
* The given Event must be acquire through the get_graph_event() method.
|
||||
*
|
||||
* \throws InvalidEventError if the given event is nullptr
|
||||
* \throws EventNotRegisteredError if the given event was not acquired with
|
||||
|
|
|
@ -39,14 +39,14 @@ public:
|
|||
RCLCPP_SMART_PTR_ALIASES_ONLY(NodeBaseInterface)
|
||||
|
||||
/// Return the name of the node.
|
||||
// \return The name of the node.
|
||||
/** \return The name of the node. */
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
const char *
|
||||
get_name() const = 0;
|
||||
|
||||
/// Return the context of the node.
|
||||
// \return SharedPtr to the node's context.
|
||||
/** \return SharedPtr to the node's context. */
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
rclcpp::context::Context::SharedPtr
|
||||
|
@ -65,7 +65,8 @@ public:
|
|||
get_rcl_node_handle() const = 0;
|
||||
|
||||
/// Return the rcl_node_t node handle in a std::shared_ptr.
|
||||
/* This handle remains valid after the Node is destroyed.
|
||||
/**
|
||||
* This handle remains valid after the Node is destroyed.
|
||||
* The actual rcl node is not finalized until it is out of scope everywhere.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
|
@ -74,7 +75,8 @@ public:
|
|||
get_shared_rcl_node_handle() = 0;
|
||||
|
||||
/// Return the rcl_node_t node handle in a std::shared_ptr.
|
||||
/* This handle remains valid after the Node is destroyed.
|
||||
/**
|
||||
* This handle remains valid after the Node is destroyed.
|
||||
* The actual rcl node is not finalized until it is out of scope everywhere.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
|
@ -113,7 +115,8 @@ public:
|
|||
get_associated_with_executor_atomic() = 0;
|
||||
|
||||
/// Return guard condition that should be notified when the internal node state changes.
|
||||
/* For example, this should be notified when a publisher is added or removed.
|
||||
/**
|
||||
* For example, this should be notified when a publisher is added or removed.
|
||||
*
|
||||
* \return the rcl_guard_condition_t if it is valid, else nullptr
|
||||
*/
|
||||
|
@ -123,7 +126,7 @@ public:
|
|||
get_notify_guard_condition() = 0;
|
||||
|
||||
/// Acquire and return a scoped lock that protects the notify guard condition.
|
||||
/* This should be used when triggering the notify guard condition. */
|
||||
/** This should be used when triggering the notify guard condition. */
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
std::unique_lock<std::recursive_mutex>
|
||||
|
|
|
@ -119,7 +119,7 @@ private:
|
|||
/// Weak references to graph events out on loan.
|
||||
std::vector<rclcpp::event::Event::WeakPtr> graph_events_;
|
||||
/// Number of graph events out on loan, used to determine if the graph should be monitored.
|
||||
/* graph_users_count_ is atomic so that it can be accessed without acquiring the graph_mutex_ */
|
||||
/** graph_users_count_ is atomic so that it can be accessed without acquiring the graph_mutex_ */
|
||||
std::atomic_size_t graph_users_count_;
|
||||
};
|
||||
|
||||
|
|
|
@ -37,7 +37,8 @@ public:
|
|||
RCLCPP_SMART_PTR_ALIASES_ONLY(NodeGraphInterface)
|
||||
|
||||
/// Return a map of existing topic names (string) to topic types (string).
|
||||
/* A topic is considered to exist when at least one publisher or subscriber
|
||||
/**
|
||||
* A topic is considered to exist when at least one publisher or subscriber
|
||||
* exists for it, whether they be local or remote to this process.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
|
@ -64,7 +65,8 @@ public:
|
|||
get_graph_guard_condition() const = 0;
|
||||
|
||||
/// Notify threads waiting on graph changes.
|
||||
/* Affects threads waiting on the notify guard condition, see:
|
||||
/**
|
||||
* Affects threads waiting on the notify guard condition, see:
|
||||
* get_notify_guard_condition(), as well as the threads waiting on graph
|
||||
* changes using a graph Event, see: wait_for_graph_change().
|
||||
*
|
||||
|
@ -84,7 +86,8 @@ public:
|
|||
notify_shutdown() = 0;
|
||||
|
||||
/// Return a graph event, which will be set anytime a graph change occurs.
|
||||
/* The graph Event object is a loan which must be returned.
|
||||
/**
|
||||
* The graph Event object is a loan which must be returned.
|
||||
* The Event object is scoped and therefore to return the load just let it go
|
||||
* out of scope.
|
||||
*/
|
||||
|
@ -94,7 +97,8 @@ public:
|
|||
get_graph_event() = 0;
|
||||
|
||||
/// Wait for a graph event to occur by waiting on an Event to become set.
|
||||
/* The given Event must be acquire through the get_graph_event() method.
|
||||
/**
|
||||
* The given Event must be acquire through the get_graph_event() method.
|
||||
*
|
||||
* \throws InvalidEventError if the given event is nullptr
|
||||
* \throws EventNotRegisteredError if the given event was not acquired with
|
||||
|
@ -108,7 +112,8 @@ public:
|
|||
std::chrono::nanoseconds timeout) = 0;
|
||||
|
||||
/// Return the number of on loan graph events, see get_graph_event().
|
||||
/* This is typically only used by the rclcpp::graph_listener::GraphListener.
|
||||
/**
|
||||
* This is typically only used by the rclcpp::graph_listener::GraphListener.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
virtual
|
||||
|
|
|
@ -216,7 +216,7 @@ private:
|
|||
};
|
||||
|
||||
|
||||
/* Return a json encoded version of the parameter intended for a dict. */
|
||||
/// Return a json encoded version of the parameter intended for a dict.
|
||||
RCLCPP_PUBLIC
|
||||
std::string
|
||||
_to_json_dict_entry(const ParameterVariant & param);
|
||||
|
@ -235,12 +235,12 @@ operator<<(std::ostream & os, const std::vector<ParameterVariant> & parameters);
|
|||
namespace std
|
||||
{
|
||||
|
||||
/* Return a json encoded version of the parameter intended for a list. */
|
||||
/// Return a json encoded version of the parameter intended for a list.
|
||||
RCLCPP_PUBLIC
|
||||
std::string
|
||||
to_string(const rclcpp::parameter::ParameterVariant & param);
|
||||
|
||||
/* Return a json encoded version of a vector of parameters, as a string*/
|
||||
/// Return a json encoded version of a vector of parameters, as a string.
|
||||
RCLCPP_PUBLIC
|
||||
std::string
|
||||
to_string(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
|
||||
|
|
|
@ -75,25 +75,25 @@ public:
|
|||
virtual ~PublisherBase();
|
||||
|
||||
/// Get the topic that this publisher publishes on.
|
||||
// \return The topic name.
|
||||
/** \return The topic name. */
|
||||
RCLCPP_PUBLIC
|
||||
const char *
|
||||
get_topic_name() const;
|
||||
|
||||
/// Get the queue size for this publisher.
|
||||
// \return The queue size.
|
||||
/** \return The queue size. */
|
||||
RCLCPP_PUBLIC
|
||||
size_t
|
||||
get_queue_size() const;
|
||||
|
||||
/// Get the global identifier for this publisher (used in rmw and by DDS).
|
||||
// \return The gid.
|
||||
/** \return The gid. */
|
||||
RCLCPP_PUBLIC
|
||||
const rmw_gid_t &
|
||||
get_gid() const;
|
||||
|
||||
/// Get the global identifier for this publisher used by intra-process communication.
|
||||
// \return The intra-process gid.
|
||||
/** \return The intra-process gid. */
|
||||
RCLCPP_PUBLIC
|
||||
const rmw_gid_t &
|
||||
get_intra_process_gid() const;
|
||||
|
|
|
@ -32,7 +32,8 @@ namespace rclcpp
|
|||
{
|
||||
|
||||
/// Factory with functions used to create a MessageT specific PublisherT.
|
||||
/* This factory class is used to encapsulate the template generated functions
|
||||
/**
|
||||
* This factory class is used to encapsulate the template generated functions
|
||||
* which are used during the creation of a Message type specific publisher
|
||||
* within a non-templated class.
|
||||
*
|
||||
|
|
|
@ -12,6 +12,112 @@
|
|||
// See the License for the specific language governing permissions and
|
||||
// limitations under the License.
|
||||
|
||||
/** \mainpage rclcpp: ROS Client Library for C++
|
||||
*
|
||||
* `rclcpp` provides the canonical C++ API for interacting with ROS.
|
||||
* It consists of these main components:
|
||||
*
|
||||
* - Nodes
|
||||
* - rclcpp::node::Node
|
||||
* - rclcpp/node.hpp
|
||||
* - Publisher
|
||||
* - rclcpp::node::Node::create_publisher()
|
||||
* - rclcpp::publisher::Publisher
|
||||
* - rclcpp::publisher::Publisher::publish()
|
||||
* - rclcpp/publisher.hpp
|
||||
* - Subscription
|
||||
* - rclcpp::node::Node::create_subscription()
|
||||
* - rclcpp::subscription::Subscription
|
||||
* - rclcpp/subscription.hpp
|
||||
* - Service Client
|
||||
* - rclcpp::node::Node::create_client()
|
||||
* - rclcpp::client::Client
|
||||
* - rclcpp/client.hpp
|
||||
* - Service Server
|
||||
* - rclcpp::node::Node::create_service()
|
||||
* - rclcpp::service::Service
|
||||
* - rclcpp/service.hpp
|
||||
* - Timer
|
||||
* - rclcpp::node::Node::create_wall_timer()
|
||||
* - rclcpp::timer::WallTimer
|
||||
* - rclcpp::timer::TimerBase
|
||||
* - rclcpp/timer.hpp
|
||||
* - Parameters:
|
||||
* - rclcpp::node::Node::set_parameters()
|
||||
* - rclcpp::node::Node::get_parameters()
|
||||
* - rclcpp::node::Node::get_parameter()
|
||||
* - rclcpp::node::Node::describe_parameters()
|
||||
* - rclcpp::node::Node::list_parameters()
|
||||
* - rclcpp::node::Node::register_param_change_callback()
|
||||
* - rclcpp::parameter::ParameterVariant
|
||||
* - rclcpp::parameter_client::AsyncParametersClient
|
||||
* - rclcpp::parameter_client::SyncParametersClient
|
||||
* - rclcpp/parameter.hpp
|
||||
* - rclcpp/parameter_client.hpp
|
||||
* - rclcpp/parameter_service.hpp
|
||||
* - Rate:
|
||||
* - rclcpp::rate::Rate
|
||||
* - rclcpp::rate::WallRate
|
||||
* - rclcpp/rate.hpp
|
||||
*
|
||||
* There are also some components which help control the execution of callbacks:
|
||||
*
|
||||
* - Executors (responsible for execution of callbacks through a blocking spin):
|
||||
* - rclcpp::spin()
|
||||
* - rclcpp::spin_some()
|
||||
* - rclcpp::spin_until_future_complete()
|
||||
* - rclcpp::executors::single_threaded_executor::SingleThreadedExecutor
|
||||
* - rclcpp::executors::single_threaded_executor::SingleThreadedExecutor::add_node()
|
||||
* - rclcpp::executors::single_threaded_executor::SingleThreadedExecutor::spin()
|
||||
* - rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor
|
||||
* - rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor::add_node()
|
||||
* - rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor::spin()
|
||||
* - rclcpp/executor.hpp
|
||||
* - rclcpp/executors.hpp
|
||||
* - rclcpp/executors/single_threaded_executor.hpp
|
||||
* - rclcpp/executors/multi_threaded_executor.hpp
|
||||
* - CallbackGroups (mechanism for enforcing concurrency rules for callbacks):
|
||||
* - rclcpp::node::Node::create_callback_group()
|
||||
* - rclcpp::callback_group::CallbackGroup
|
||||
* - rclcpp/callback_group.hpp
|
||||
*
|
||||
* Additionally, there are some methods for introspecting the ROS graph:
|
||||
*
|
||||
* - Graph Events (a waitable event object that wakes up when the graph changes):
|
||||
* - rclcpp::node::Node::get_graph_event()
|
||||
* - rclcpp::node::Node::wait_for_graph_change()
|
||||
* - rclcpp::event::Event
|
||||
* - List topic names and types:
|
||||
* - rclcpp::node::Node::get_topic_names_and_types()
|
||||
* - Get the number of publishers or subscribers on a topic:
|
||||
* - rclcpp::node::Node::count_publishers()
|
||||
* - rclcpp::node::Node::count_subscribers()
|
||||
*
|
||||
* Finally, there are many internal API's and utilities:
|
||||
*
|
||||
* - Exceptions:
|
||||
* - rclcpp/exceptions.hpp
|
||||
* - Allocator related items:
|
||||
* - rclcpp/allocator/allocator_common.hpp
|
||||
* - rclcpp/allocator/allocator_deleter.hpp
|
||||
* - Memory management tools:
|
||||
* - rclcpp/memory_strategies.hpp
|
||||
* - rclcpp/memory_strategy.hpp
|
||||
* - rclcpp/message_memory_strategy.hpp
|
||||
* - rclcpp/strategies/allocator_memory_strategy.hpp
|
||||
* - rclcpp/strategies/message_pool_memory_strategy.hpp
|
||||
* - Context object which is shared amongst multiple Nodes:
|
||||
* - rclcpp::context::Context
|
||||
* - rclcpp/context.hpp
|
||||
* - rclcpp/contexts/default_context.hpp
|
||||
* - Various utilities:
|
||||
* - rclcpp/function_traits.hpp
|
||||
* - rclcpp/macros.hpp
|
||||
* - rclcpp/scope_exit.hpp
|
||||
* - rclcpp/utilities.hpp
|
||||
* - rclcpp/visibility_control.hpp
|
||||
*/
|
||||
|
||||
#ifndef RCLCPP__RCLCPP_HPP_
|
||||
#define RCLCPP__RCLCPP_HPP_
|
||||
|
||||
|
|
|
@ -85,7 +85,7 @@ public:
|
|||
get_intra_process_subscription_handle() const;
|
||||
|
||||
/// Borrow a new message.
|
||||
// \return Shared pointer to the fresh message.
|
||||
/** \return Shared pointer to the fresh message. */
|
||||
virtual std::shared_ptr<void>
|
||||
create_message() = 0;
|
||||
/// Check if we need to handle the message, and execute the callback if we do.
|
||||
|
@ -97,9 +97,10 @@ public:
|
|||
handle_message(std::shared_ptr<void> & message, const rmw_message_info_t & message_info) = 0;
|
||||
|
||||
/// Return the message borrowed in create_message.
|
||||
// \param[in] Shared pointer to the returned message.
|
||||
/** \param[in] message Shared pointer to the returned message. */
|
||||
virtual void
|
||||
return_message(std::shared_ptr<void> & message) = 0;
|
||||
|
||||
virtual void
|
||||
handle_intra_process_message(
|
||||
rcl_interfaces::msg::IntraProcessMessage & ipm,
|
||||
|
@ -192,6 +193,8 @@ public:
|
|||
any_callback_.dispatch(typed_message, message_info);
|
||||
}
|
||||
|
||||
/// Return the loaned message.
|
||||
/** \param message message to be returned */
|
||||
void return_message(std::shared_ptr<void> & message)
|
||||
{
|
||||
auto typed_message = std::static_pointer_cast<MessageT>(message);
|
||||
|
|
|
@ -33,7 +33,8 @@ namespace rclcpp
|
|||
{
|
||||
|
||||
/// Factory with functions used to create a Subscription<MessageT>.
|
||||
/* This factory class is used to encapsulate the template generated functions
|
||||
/**
|
||||
* This factory class is used to encapsulate the template generated functions
|
||||
* which are used during the creation of a Message type specific subscription
|
||||
* within a non-templated class.
|
||||
*
|
||||
|
|
|
@ -64,13 +64,13 @@ public:
|
|||
get_timer_handle();
|
||||
|
||||
/// Check how long the timer has until its next scheduled callback.
|
||||
// \return A std::chrono::duration representing the relative time until the next callback.
|
||||
/** \return A std::chrono::duration representing the relative time until the next callback. */
|
||||
RCLCPP_PUBLIC
|
||||
std::chrono::nanoseconds
|
||||
time_until_trigger();
|
||||
|
||||
/// Is the clock steady (i.e. is the time between ticks constant?)
|
||||
// \return True if the clock used by this timer is steady.
|
||||
/** \return True if the clock used by this timer is steady. */
|
||||
virtual bool is_steady() = 0;
|
||||
|
||||
/// Check if the timer is ready to trigger the callback.
|
||||
|
|
|
@ -57,7 +57,7 @@ void
|
|||
init(int argc, char * argv[]);
|
||||
|
||||
/// Check rclcpp's status.
|
||||
// \return True if SIGINT hasn't fired yet, false otherwise.
|
||||
/** \return True if SIGINT hasn't fired yet, false otherwise. */
|
||||
RCLCPP_PUBLIC
|
||||
bool
|
||||
ok();
|
||||
|
@ -68,7 +68,7 @@ void
|
|||
shutdown();
|
||||
|
||||
/// Register a function to be called when shutdown is called.
|
||||
/* Calling the callbacks is the last thing shutdown() does. */
|
||||
/** Calling the callbacks is the last thing shutdown() does. */
|
||||
RCLCPP_PUBLIC
|
||||
void
|
||||
on_shutdown(std::function<void(void)> callback);
|
||||
|
@ -81,7 +81,7 @@ on_shutdown(std::function<void(void)> callback);
|
|||
* that the same guard condition is not reused across waitsets (e.g., when
|
||||
* using multiple executors in the same process). Will throw an exception if
|
||||
* initialization of the guard condition fails.
|
||||
* \param[waitset] waitset Pointer to the rcl_wait_set_t that will be using the
|
||||
* \param waitset Pointer to the rcl_wait_set_t that will be using the
|
||||
* resulting guard condition.
|
||||
* \return Pointer to the guard condition.
|
||||
*/
|
||||
|
@ -95,7 +95,7 @@ get_sigint_guard_condition(rcl_wait_set_t * waitset);
|
|||
* to get a sigint guard condition, then you should call release_sigint_guard_condition()
|
||||
* when you're done, to free that condition. Will throw an exception if
|
||||
* get_sigint_guard_condition() wasn't previously called for the given waitset.
|
||||
* \param[waitset] waitset Pointer to the rcl_wait_set_t that was using the
|
||||
* \param waitset Pointer to the rcl_wait_set_t that was using the
|
||||
* resulting guard condition.
|
||||
*/
|
||||
RCLCPP_PUBLIC
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue