rclcpp
master
C++ ROS Client Library API
|
Context which encapsulates shared state between nodes and other similar entities. More...
#include <context.hpp>
Public Types | |
using | OnShutdownCallback = std::function< void()> |
Public Member Functions | |
Context () | |
Default constructor, after which the Context is still not "initialized". More... | |
virtual | ~Context () |
virtual void | init (int argc, char const *const argv[], const rclcpp::InitOptions &init_options=rclcpp::InitOptions()) |
Initialize the context, and the underlying elements like the rcl context. More... | |
bool | is_valid () const |
Return true if the context is valid, otherwise false. More... | |
const rclcpp::InitOptions & | get_init_options () const |
Return the init options used during init. More... | |
rclcpp::InitOptions | get_init_options () |
Return a copy of the init options used during init. More... | |
std::string | shutdown_reason () |
Return the shutdown reason, or empty string if not shutdown. More... | |
virtual bool | shutdown (const std::string &reason) |
Shutdown the context, making it uninitialized and therefore invalid for derived entities. More... | |
virtual OnShutdownCallback | on_shutdown (OnShutdownCallback callback) |
Add a on_shutdown callback to be called when shutdown is called for this context. More... | |
const std::vector< OnShutdownCallback > & | get_on_shutdown_callbacks () const |
Return the shutdown callbacks as const. More... | |
std::vector< OnShutdownCallback > & | get_on_shutdown_callbacks () |
Return the shutdown callbacks. More... | |
std::shared_ptr< rcl_context_t > | get_rcl_context () |
Return the internal rcl context. More... | |
bool | sleep_for (const std::chrono::nanoseconds &nanoseconds) |
Sleep for a given period of time or until shutdown() is called. More... | |
virtual void | interrupt_all_sleep_for () |
Interrupt any blocking sleep_for calls, causing them to return immediately and return true. More... | |
rcl_guard_condition_t * | get_interrupt_guard_condition (rcl_wait_set_t *wait_set) |
Get a handle to the guard condition which is triggered when interrupted. More... | |
void | release_interrupt_guard_condition (rcl_wait_set_t *wait_set) |
Release the previously allocated guard condition which is triggered when interrupted. More... | |
void | release_interrupt_guard_condition (rcl_wait_set_t *wait_set, const std::nothrow_t &) noexcept |
Nothrow version of release_interrupt_guard_condition(), logs to RCLCPP_ERROR instead. More... | |
virtual void | interrupt_all_wait_sets () |
Interrupt any blocking executors, or wait sets associated with this context. More... | |
template<typename SubContext , typename ... Args> | |
std::shared_ptr< SubContext > | get_sub_context (Args &&... args) |
Return a singleton instance for the SubContext type, constructing one if necessary. More... | |
Public Member Functions inherited from std::enable_shared_from_this< Context > | |
T | enable_shared_from_this (T... args) |
T | operator= (T... args) |
T | shared_from_this (T... args) |
T | ~enable_shared_from_this (T... args) |
Protected Member Functions | |
virtual void | clean_up () |
Context which encapsulates shared state between nodes and other similar entities.
A context also represents the lifecycle between init and shutdown of rclcpp. It is often used in conjunction with rclcpp::init, or rclcpp::init_local, and rclcpp::shutdown.
using rclcpp::Context::OnShutdownCallback = std::function<void ()> |
rclcpp::Context::Context | ( | ) |
Default constructor, after which the Context is still not "initialized".
Every context which is constructed is added to a global vector of contexts, which is used by the signal handler to conditionally shutdown each context on SIGINT. See the shutdown_on_sigint option in the InitOptions class.
|
virtual |
|
virtual |
Initialize the context, and the underlying elements like the rcl context.
This method must be called before passing this context to things like the constructor of Node. It must also be called before trying to shutdown the context.
Note that this function does not setup any signal handlers, so if you want it to be shutdown by the signal handler, then you need to either install them manually with rclcpp::install_signal_handers() or use rclcpp::init(). In addition to installing the signal handlers, the shutdown_on_sigint of the InitOptions needs to be true
for this context to be shutdown by the signal handler, otherwise it will be passed over.
After calling this method, shutdown() can be called to invalidate the context for derived entities, e.g. nodes, guard conditions, etc. However, the underlying rcl context is not finalized until this Context's destructor is called or this function is called again. Allowing this class to go out of scope and get destructed or calling this function a second time while derived entities are still using the context is undefined behavior and should be avoided. It's a good idea to not reuse context objects and instead create a new one each time you need to shutdown and init again. This allows derived entities to hold on to shard pointers to the first context object until they are done.
This function is thread-safe.
[in] | argc | number of arguments |
[in] | argv | argument array which may contain arguments intended for ROS |
[in] | init_options | initialization options for rclcpp and underlying layers |
ContextAlreadyInitialized | if called if init is called more than once |
anything | rclcpp::exceptions::throw_from_rcl_error can throw. |
std::runtime_error | if the global logging configure mutex is NULL |
exceptions::UnknownROSArgsError | if there are unknown ROS arguments |
bool rclcpp::Context::is_valid | ( | ) | const |
Return true if the context is valid, otherwise false.
The context is valid if it has been initialized but not shutdown.
This function is thread-safe. This function is lock free so long as pointers and uint64_t atomics are lock free.
const rclcpp::InitOptions& rclcpp::Context::get_init_options | ( | ) | const |
Return the init options used during init.
rclcpp::InitOptions rclcpp::Context::get_init_options | ( | ) |
Return a copy of the init options used during init.
std::string rclcpp::Context::shutdown_reason | ( | ) |
Return the shutdown reason, or empty string if not shutdown.
This function is thread-safe.
|
virtual |
Shutdown the context, making it uninitialized and therefore invalid for derived entities.
Several things happen when the context is shutdown, in this order:
The underlying rcl context is not finalized by this function.
This function is thread-safe.
[in] | reason | the description of why shutdown happened |
various | exceptions derived from rclcpp::exceptions::RCLError, if rcl_shutdown fails |
|
virtual |
Add a on_shutdown callback to be called when shutdown is called for this context.
These callbacks will be called in the order they are added as the second to last step in shutdown().
When shutdown occurs due to the signal handler, these callbacks are run asynchronoulsy in the dedicated singal handling thread.
Also, shutdown() may be called from the destructor of this function. Therefore, it is not safe to throw exceptions from these callbacks. Instead, log errors or use some other mechanism to indicate an error has occurred.
On shutdown callbacks may be registered before init and after shutdown, and persist on repeated init's.
[in] | callback | the on shutdown callback to be registered |
const std::vector<OnShutdownCallback>& rclcpp::Context::get_on_shutdown_callbacks | ( | ) | const |
Return the shutdown callbacks as const.
Using the returned reference is not thread-safe with calls that modify the list of "on shutdown" callbacks, i.e. on_shutdown().
std::vector<OnShutdownCallback>& rclcpp::Context::get_on_shutdown_callbacks | ( | ) |
Return the shutdown callbacks.
Using the returned reference is not thread-safe with calls that modify the list of "on shutdown" callbacks, i.e. on_shutdown().
std::shared_ptr<rcl_context_t> rclcpp::Context::get_rcl_context | ( | ) |
Return the internal rcl context.
bool rclcpp::Context::sleep_for | ( | const std::chrono::nanoseconds & | nanoseconds | ) |
Sleep for a given period of time or until shutdown() is called.
This function can be interrupted early if:
[in] | nanoseconds | A std::chrono::duration representing how long to sleep for. |
|
virtual |
Interrupt any blocking sleep_for calls, causing them to return immediately and return true.
rcl_guard_condition_t* rclcpp::Context::get_interrupt_guard_condition | ( | rcl_wait_set_t * | wait_set | ) |
Get a handle to the guard condition which is triggered when interrupted.
This guard condition is triggered any time interrupt_all_wait_sets() is called, which may be called by the user, or shutdown(). And in turn, shutdown() may be called by the user, the destructor of this context, or the signal handler if installed and shutdown_on_sigint is true for this context.
The first time that this function is called for a given wait set a new guard condition will be created and returned; thereafter the same guard condition will be returned for the same wait set. This mechanism is designed to ensure that the same guard condition is not reused across wait sets (e.g., when using multiple executors in the same process). This method will throw an exception if initialization of the guard condition fails.
The returned guard condition needs to be released with the release_interrupt_guard_condition() method in order to reclaim resources.
[in] | wait_set | Pointer to the rcl_wait_set_t that will be using the resulting guard condition. |
anything | rclcpp::exceptions::throw_from_rcl_error can throw. |
void rclcpp::Context::release_interrupt_guard_condition | ( | rcl_wait_set_t * | wait_set | ) |
Release the previously allocated guard condition which is triggered when interrupted.
If you previously called get_interrupt_guard_condition() for a given wait set to get a interrupt guard condition, then you should call release_interrupt_guard_condition() when you're done, to free that condition. Will throw an exception if get_interrupt_guard_condition() wasn't previously called for the given wait set.
After calling this, the pointer returned by get_interrupt_guard_condition() for the given wait_set is invalid.
[in] | wait_set | Pointer to the rcl_wait_set_t that was using the resulting guard condition. |
anything | rclcpp::exceptions::throw_from_rcl_error can throw. |
std::runtime_error | if a nonexistent wait set is trying to release sigint guard condition. |
|
noexcept |
Nothrow version of release_interrupt_guard_condition(), logs to RCLCPP_ERROR instead.
|
virtual |
Interrupt any blocking executors, or wait sets associated with this context.
|
inline |
Return a singleton instance for the SubContext type, constructing one if necessary.
|
protectedvirtual |