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

refactor init to allow for non-global init #587

Merged
merged 15 commits into from Nov 30, 2018
Merged
Show file tree
Hide file tree
Changes from 12 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
1 change: 1 addition & 0 deletions rclcpp/CMakeLists.txt
Expand Up @@ -40,6 +40,7 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/executors/multi_threaded_executor.cpp
src/rclcpp/executors/single_threaded_executor.cpp
src/rclcpp/graph_listener.cpp
src/rclcpp/init_options.cpp
src/rclcpp/intra_process_manager.cpp
src/rclcpp/intra_process_manager_impl.cpp
src/rclcpp/logger.cpp
Expand Down
1 change: 1 addition & 0 deletions rclcpp/include/rclcpp/client.hpp
Expand Up @@ -110,6 +110,7 @@ class ClientBase

rclcpp::node_interfaces::NodeGraphInterface::WeakPtr node_graph_;
std::shared_ptr<rcl_node_t> node_handle_;
std::shared_ptr<rclcpp::Context> context_;

std::shared_ptr<rcl_client_t> client_handle_;
};
Expand Down
212 changes: 207 additions & 5 deletions rclcpp/include/rclcpp/context.hpp
Expand Up @@ -15,34 +15,208 @@
#ifndef RCLCPP__CONTEXT_HPP_
#define RCLCPP__CONTEXT_HPP_

#include <iostream>
#include <functional>
#include <memory>
#include <mutex>
#include <string>
#include <typeindex>
#include <typeinfo>
#include <unordered_map>
#include <utility>
#include <vector>

#include "rcl/context.h"
#include "rclcpp/init_options.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/visibility_control.hpp"
#include "rmw/rmw.h"

namespace rclcpp
{

class Context
/// Thrown when init is called on an already initialized context.
class ContextAlreadyInitialized : public std::runtime_error
{
public:
ContextAlreadyInitialized()
: std::runtime_error("context is already initialized") {}
};

/// 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.
*/
class Context : public std::enable_shared_from_this<Context>
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(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.
*/
RCLCPP_PUBLIC
Context();

RCLCPP_PUBLIC
virtual
~Context();

/// 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.
*
* \param[in] argc number of arguments
* \param[in] argv argument array which may contain arguments intended for ROS
* \param[in] init_options initialization options for rclcpp and underlying layers
* \throw ContextAlreadyInitialized if called if init is called more than once
*/
RCLCPP_PUBLIC
virtual
void
init(
int argc,
char const * const argv[],
const rclcpp::InitOptions & init_options = rclcpp::InitOptions());

/// 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.
*
* \return true if valid, otherwise false
*/
RCLCPP_PUBLIC
bool
is_valid() const;

/// Return the init options used during init.
RCLCPP_PUBLIC
const rclcpp::InitOptions &
get_init_options() const;

/// Return a copy of the init options used during init.
RCLCPP_PUBLIC
rclcpp::InitOptions
get_init_options();

/// Return the shutdown reason, or empty string if not shutdown.
/**
* This function is thread-safe.
*/
RCLCPP_PUBLIC
std::string
shutdown_reason();

/// Shutdown the context, making it uninitialized and therefore invalid for derived entities.
/**
* Several things happen when the context is shutdown, in this order:
*
* - acquires a lock to prevent race conditions with init, on_shutdown, etc.
* - if the context is not initialized, return false
* - rcl_shutdown() is called on the internal rcl_context_t instance
* - the shutdown reason is set
* - each on_shutdown callback is called, in the order that they were added
* - if notify_all is true, rclcpp::notify_all is called to unblock some ROS functions
*
* The underlying rcl context is not finalized by this function.
*
* This function is thread-safe.
*
* \param[in] reason the description of why shutdown happened
* \param[in] notify_all if true, then rclcpp::notify_all will be called
* \return true if shutdown was successful, false if context was already shutdown
* \throw various exceptions derived from RCLErrorBase, if rcl_shutdown fails
*/
RCLCPP_PUBLIC
virtual
bool
shutdown(const std::string & reason, bool notify_all = true);

using OnShutdownCallback = std::function<void ()>;

/// 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().
*
* These callbacks may be run in the signal handler as the signal handler
* may call shutdown() on this context.
* 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.
*
* \param[in] callback the on shutdown callback to be registered
* \return the callback passed, for convenience when storing a passed lambda
*/
RCLCPP_PUBLIC
virtual
OnShutdownCallback
on_shutdown(OnShutdownCallback callback);

/// 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().
*/
RCLCPP_PUBLIC
const std::vector<OnShutdownCallback> &
get_on_shutdown_callbacks() const;

/// 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().
*/
RCLCPP_PUBLIC
std::vector<OnShutdownCallback> &
get_on_shutdown_callbacks();

/// Return the internal rcl context.
RCLCPP_PUBLIC
std::shared_ptr<rcl_context_t>
get_rcl_context();

/// Return a singleton instance for the SubContext type, constructing one if necessary.
template<typename SubContext, typename ... Args>
std::shared_ptr<SubContext>
get_sub_context(Args && ... args)
{
std::lock_guard<std::mutex> lock(mutex_);
std::lock_guard<std::recursive_mutex> lock(sub_contexts_mutex_);

std::type_index type_i(typeid(SubContext));
std::shared_ptr<SubContext> sub_context;
Expand All @@ -62,13 +236,41 @@ class Context
return sub_context;
}

protected:
// Called by constructor and destructor to clean up by finalizing the
// shutdown rcl context and preparing for a new init cycle.
RCLCPP_PUBLIC
virtual
void
clean_up();

private:
RCLCPP_DISABLE_COPY(Context)

// This mutex is recursive so that the destructor can ensure atomicity
// between is_initialized and shutdown.
std::recursive_mutex init_mutex_;
std::shared_ptr<rcl_context_t> rcl_context_;
rclcpp::InitOptions init_options_;
std::string shutdown_reason_;

std::unordered_map<std::type_index, std::shared_ptr<void>> sub_contexts_;
std::mutex mutex_;
// This mutex is recursive so that the constructor of a sub context may
// attempt to acquire another sub context.
std::recursive_mutex sub_contexts_mutex_;

std::vector<OnShutdownCallback> on_shutdown_callbacks_;
std::mutex on_shutdown_callbacks_mutex_;
};

/// Return a copy of the list of context shared pointers.
/**
* This function is thread-safe.
*/
RCLCPP_PUBLIC
std::vector<Context::SharedPtr>
get_contexts();

} // namespace rclcpp

#endif // RCLCPP__CONTEXT_HPP_
10 changes: 8 additions & 2 deletions rclcpp/include/rclcpp/executor.hpp
Expand Up @@ -28,9 +28,10 @@
#include "rcl/guard_condition.h"
#include "rcl/wait.h"

#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/memory_strategies.hpp"
#include "rclcpp/memory_strategy.hpp"
#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp/visibility_control.hpp"

Expand Down Expand Up @@ -66,13 +67,15 @@ to_string(const FutureReturnCode & future_return_code);
struct ExecutorArgs
{
memory_strategy::MemoryStrategy::SharedPtr memory_strategy;
std::shared_ptr<rclcpp::Context> context;
size_t max_conditions = 0;
};

static inline ExecutorArgs create_default_executor_arguments()
{
ExecutorArgs args;
args.memory_strategy = memory_strategies::create_default_strategy();
args.context = rclcpp::contexts::default_context::get_global_default_context();
args.max_conditions = 0;
return args;
}
Expand Down Expand Up @@ -237,7 +240,7 @@ class Executor
}
std::chrono::nanoseconds timeout_left = timeout_ns;

while (rclcpp::ok()) {
while (rclcpp::ok(this->context_)) {
// Do one item of work.
spin_once(timeout_left);
// Check if the future is set, return SUCCESS if it is.
Expand Down Expand Up @@ -353,6 +356,9 @@ class Executor
/// The memory strategy: an interface for handling user-defined memory allocation strategies.
memory_strategy::MemoryStrategy::SharedPtr memory_strategy_;

/// The context associated with this executor.
std::shared_ptr<rclcpp::Context> context_;

private:
RCLCPP_DISABLE_COPY(Executor)

Expand Down
4 changes: 3 additions & 1 deletion rclcpp/include/rclcpp/graph_listener.hpp
Expand Up @@ -23,6 +23,7 @@

#include "rcl/guard_condition.h"
#include "rcl/wait.h"
#include "rclcpp/context.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
#include "rclcpp/visibility_control.hpp"
Expand Down Expand Up @@ -62,7 +63,7 @@ class GraphListener : public std::enable_shared_from_this<GraphListener>
{
public:
RCLCPP_PUBLIC
GraphListener();
explicit GraphListener(std::shared_ptr<rclcpp::Context> parent_context);

RCLCPP_PUBLIC
virtual ~GraphListener();
Expand Down Expand Up @@ -164,6 +165,7 @@ class GraphListener : public std::enable_shared_from_this<GraphListener>
std::vector<rclcpp::node_interfaces::NodeGraphInterface *> node_graph_interfaces_;

rcl_guard_condition_t interrupt_guard_condition_ = rcl_get_zero_initialized_guard_condition();
std::shared_ptr<rcl_context_t> interrupt_guard_condition_context_;
rcl_guard_condition_t * shutdown_guard_condition_;
rcl_wait_set_t wait_set_ = rcl_get_zero_initialized_wait_set();
};
Expand Down