Skip to content

Commit

Permalink
fix virtual dispatch issues identified by clang-tidy (#1816)
Browse files Browse the repository at this point in the history
* fix virtual dispatch issues identified by clang-tidy

Signed-off-by: William Woodall <william@osrfoundation.org>

* fix up to reduce code duplication

Signed-off-by: William Woodall <william@osrfoundation.org>

* uncrustify

Signed-off-by: William Woodall <william@osrfoundation.org>

* avoid returning temporaries

Signed-off-by: William Woodall <william@osrfoundation.org>

* uncrustify

Signed-off-by: William Woodall <william@osrfoundation.org>

* add docs about overriding methods used in constructors

Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed Jun 22, 2022
1 parent 86a9d58 commit dbded5c
Show file tree
Hide file tree
Showing 10 changed files with 112 additions and 23 deletions.
7 changes: 5 additions & 2 deletions rclcpp/include/rclcpp/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -183,6 +183,11 @@ class Context : public std::enable_shared_from_this<Context>
*
* This function is thread-safe.
*
* Note that if you override this method, but leave shutdown to be called in
* the destruction of this base class, it will not call the overridden
* version from your base class.
* So you need to ensure you call your class's shutdown() in its destructor.
*
* \param[in] reason the description of why shutdown happened
* \return true if shutdown was successful, false if context was already shutdown
* \throw various exceptions derived from rclcpp::exceptions::RCLError, if rcl_shutdown fails
Expand Down Expand Up @@ -318,7 +323,6 @@ class Context : public std::enable_shared_from_this<Context>

/// Interrupt any blocking sleep_for calls, causing them to return immediately and return true.
RCLCPP_PUBLIC
virtual
void
interrupt_all_sleep_for();

Expand Down Expand Up @@ -351,7 +355,6 @@ class Context : public std::enable_shared_from_this<Context>
// 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();

Expand Down
5 changes: 5 additions & 0 deletions rclcpp/include/rclcpp/graph_listener.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,11 @@ class GraphListener : public std::enable_shared_from_this<GraphListener>
* If start_if_not_started() was never called, this function still succeeds,
* but start_if_not_started() still cannot be called after this function.
*
* Note that if you override this method, but leave shutdown to be called in
* the destruction of this base class, it will not call the overridden
* version from your base class.
* So you need to ensure you call your class's shutdown() in its destructor.
*
* \throws rclcpp::execptions::RCLError from rcl_guard_condition_fini()
* \throws rclcpp::execptions::RCLError from rcl_wait_set_fini()
* \throws std::system_error anything std::mutex::lock() throws
Expand Down
10 changes: 9 additions & 1 deletion rclcpp/include/rclcpp/node_interfaces/node_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,14 +39,22 @@ class NodeBase : public NodeBaseInterface, public std::enable_shared_from_this<N
public:
RCLCPP_SMART_PTR_ALIASES_ONLY(NodeBase)

/// Constructor.
/**
* If nullptr (default) is given for the default_callback_group, one will
* be created by the constructor using the create_callback_group() method,
* but virtual dispatch will not occur so overrides of that method will not
* be used.
*/
RCLCPP_PUBLIC
NodeBase(
const std::string & node_name,
const std::string & namespace_,
rclcpp::Context::SharedPtr context,
const rcl_node_options_t & rcl_node_options,
bool use_intra_process_default,
bool enable_topic_statistics_default);
bool enable_topic_statistics_default,
rclcpp::CallbackGroup::SharedPtr default_callback_group = nullptr);

RCLCPP_PUBLIC
virtual
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,18 @@ class NodeLoggingInterface
~NodeLoggingInterface() = default;

/// Return the logger of the node.
/** \return The logger of the node. */
/**
* \return The logger of the node.
*/
RCLCPP_PUBLIC
virtual
rclcpp::Logger
get_logger() const = 0;

/// Return the logger name associated with the node.
/** \return The logger name associated with the node. */
/**
* \return The logger name associated with the node.
*/
RCLCPP_PUBLIC
virtual
const char *
Expand Down
15 changes: 15 additions & 0 deletions rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,16 @@ class NodeParameters : public NodeParametersInterface
public:
RCLCPP_SMART_PTR_ALIASES_ONLY(NodeParameters)

/// Constructor.
/**
* If using automatically_declare_parameters_from_overrides, overrides of
* get_parameter_overrides(), has_parameter(), declare_parameter() will not
* be respected.
* If this is an issue, pass false for
* automatically_declare_parameters_from_overrides and invoke
* perform_automatically_declare_parameters_from_overrides() manually after
* construction.
*/
RCLCPP_PUBLIC
NodeParameters(
const node_interfaces::NodeBaseInterface::SharedPtr node_base,
Expand Down Expand Up @@ -186,6 +196,11 @@ class NodeParameters : public NodeParametersInterface

using CallbacksContainerType = std::list<OnSetParametersCallbackHandle::WeakPtr>;

protected:
RCLCPP_PUBLIC
void
perform_automatically_declare_parameters_from_overrides();

private:
RCLCPP_DISABLE_COPY(NodeParameters)

Expand Down
4 changes: 3 additions & 1 deletion rclcpp/src/rclcpp/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,9 @@ Context::~Context()
// this will not prevent errors, but will maybe make them easier to reproduce
std::lock_guard<std::recursive_mutex> lock(init_mutex_);
try {
this->shutdown("context destructor was called while still not shutdown");
// Cannot rely on virtual dispatch in a destructor, so explicitly use the
// shutdown() provided by this base class.
Context::shutdown("context destructor was called while still not shutdown");
// at this point it is shutdown and cannot reinit
// clean_up will finalize the rcl context
this->clean_up();
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/graph_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ GraphListener::GraphListener(const std::shared_ptr<Context> & parent_context)

GraphListener::~GraphListener()
{
this->shutdown(std::nothrow);
GraphListener::shutdown(std::nothrow);
}

void GraphListener::init_wait_set()
Expand Down
14 changes: 9 additions & 5 deletions rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,12 +37,13 @@ NodeBase::NodeBase(
rclcpp::Context::SharedPtr context,
const rcl_node_options_t & rcl_node_options,
bool use_intra_process_default,
bool enable_topic_statistics_default)
bool enable_topic_statistics_default,
rclcpp::CallbackGroup::SharedPtr default_callback_group)
: context_(context),
use_intra_process_default_(use_intra_process_default),
enable_topic_statistics_default_(enable_topic_statistics_default),
node_handle_(nullptr),
default_callback_group_(nullptr),
default_callback_group_(default_callback_group),
associated_with_executor_(false),
notify_guard_condition_(context),
notify_guard_condition_is_valid_(false)
Expand Down Expand Up @@ -128,9 +129,12 @@ NodeBase::NodeBase(
delete node;
});

// Create the default callback group.
using rclcpp::CallbackGroupType;
default_callback_group_ = create_callback_group(CallbackGroupType::MutuallyExclusive);
// Create the default callback group, if needed.
if (nullptr == default_callback_group_) {
using rclcpp::CallbackGroupType;
default_callback_group_ =
NodeBase::create_callback_group(CallbackGroupType::MutuallyExclusive);
}

// Indicate the notify_guard_condition is now valid.
notify_guard_condition_is_valid_ = true;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ using rclcpp::node_interfaces::NodeLogging;
NodeLogging::NodeLogging(rclcpp::node_interfaces::NodeBaseInterface * node_base)
: node_base_(node_base)
{
logger_ = rclcpp::get_logger(this->get_logger_name());
logger_ = rclcpp::get_logger(NodeLogging::get_logger_name());
}

NodeLogging::~NodeLogging()
Expand Down
68 changes: 58 additions & 10 deletions rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,31 @@

using rclcpp::node_interfaces::NodeParameters;

RCLCPP_LOCAL
void
local_perform_automatically_declare_parameters_from_overrides(
const std::map<std::string, rclcpp::ParameterValue> & parameter_overrides,
std::function<bool(const std::string &)> has_parameter,
std::function<void(
const std::string &,
const rclcpp::ParameterValue &,
const rcl_interfaces::msg::ParameterDescriptor &,
bool)>
declare_parameter)
{
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.dynamic_typing = true;
for (const auto & pair : parameter_overrides) {
if (!has_parameter(pair.first)) {
declare_parameter(
pair.first,
pair.second,
descriptor,
true);
}
}
}

NodeParameters::NodeParameters(
const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
Expand Down Expand Up @@ -101,20 +126,43 @@ NodeParameters::NodeParameters(
// If asked, initialize any parameters that ended up in the initial parameter values,
// but did not get declared explcitily by this point.
if (automatically_declare_parameters_from_overrides) {
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.dynamic_typing = true;
for (const auto & pair : this->get_parameter_overrides()) {
if (!this->has_parameter(pair.first)) {
this->declare_parameter(
pair.first,
pair.second,
descriptor,
true);
using namespace std::placeholders;
local_perform_automatically_declare_parameters_from_overrides(
this->get_parameter_overrides(),
std::bind(&NodeParameters::has_parameter, this, _1),
[this](
const std::string & name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
bool ignore_override)
{
NodeParameters::declare_parameter(
name, default_value, parameter_descriptor, ignore_override);
}
}
);
}
}

void
NodeParameters::perform_automatically_declare_parameters_from_overrides()
{
local_perform_automatically_declare_parameters_from_overrides(
this->get_parameter_overrides(),
[this](const std::string & name) {
return this->has_parameter(name);
},
[this](
const std::string & name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
bool ignore_override)
{
this->declare_parameter(
name, default_value, parameter_descriptor, ignore_override);
}
);
}

NodeParameters::~NodeParameters()
{}

Expand Down

0 comments on commit dbded5c

Please sign in to comment.