Skip to content

Commit

Permalink
Merge branch 'rolling' into asoragna/warm-up-executor
Browse files Browse the repository at this point in the history
  • Loading branch information
mergify[bot] authored Aug 29, 2024
2 parents cf2280c + ee94bc6 commit 1b5de29
Show file tree
Hide file tree
Showing 37 changed files with 433 additions and 340 deletions.
5 changes: 5 additions & 0 deletions rclcpp/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package rclcpp
^^^^^^^^^^^^^^^^^^^^^^^^^^^^

28.3.3 (2024-07-29)
-------------------
* Only compile the tests once. (`#2590 <https://github.com/ros2/rclcpp/issues/2590>`_)
* Contributors: Chris Lalancette

28.3.2 (2024-07-24)
-------------------
* Updated rcpputils path API (`#2579 <https://github.com/ros2/rclcpp/issues/2579>`_)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,9 +31,15 @@ namespace executors
/// Static executor implementation
/**
* This executor is a static version of the original single threaded executor.
* It's static because it doesn't reconstruct the executable list for every iteration.
* It contains some performance optimization to avoid unnecessary reconstructions of
* the executable list for every iteration.
* All nodes, callbackgroups, timers, subscriptions etc. are created before
* spin() is called, and modified only when an entity is added/removed to/from a node.
* This executor is deprecated because these performance improvements have now been
* applied to all other executors.
* This executor is also considered unstable due to known bugs.
* See the unit-tests that are only applied to `StandardExecutors` for information
* on the known limitations.
*
* To run this executor instead of SingleThreadedExecutor replace:
* rclcpp::executors::SingleThreadedExecutor exec;
Expand All @@ -44,7 +50,8 @@ namespace executors
* exec.spin();
* exec.remove_node(node);
*/
class StaticSingleThreadedExecutor : public rclcpp::Executor
class [[deprecated("Use rclcpp::executors::SingleThreadedExecutor")]] StaticSingleThreadedExecutor
: public rclcpp::Executor
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(StaticSingleThreadedExecutor)
Expand Down
120 changes: 66 additions & 54 deletions rclcpp/include/rclcpp/parameter_event_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,19 +67,23 @@ struct ParameterEventCallbackHandle
* The first step is to instantiate a ParameterEventHandler, providing a ROS node to use
* to create any required subscriptions:
*
* auto param_handler = std::make_shared<rclcpp::ParameterEventHandler>(node);
* ```cpp
* auto param_handler = std::make_shared<rclcpp::ParameterEventHandler>(node);
* ```
*
* Next, you can supply a callback to the add_parameter_callback method, as follows:
*
* auto cb1 = [&node](const rclcpp::Parameter & p) {
* RCLCPP_INFO(
* node->get_logger(),
* "cb1: Received an update to parameter \"%s\" of type %s: \"%ld\"",
* p.get_name().c_str(),
* p.get_type_name().c_str(),
* p.as_int());
* };
* auto handle1 = param_handler->add_parameter_callback("an_int_param", cb1);
* ```cpp
* auto cb1 = [&node](const rclcpp::Parameter & p) {
* RCLCPP_INFO(
* node->get_logger(),
* "cb1: Received an update to parameter \"%s\" of type %s: \"%ld\"",
* p.get_name().c_str(),
* p.get_type_name().c_str(),
* p.as_int());
* };
* auto handle1 = param_handler->add_parameter_callback("an_int_param", cb1);
* ```
*
* In this case, we didn't supply a node name (the third, optional, parameter) so the
* default will be to monitor for changes to the "an_int_param" parameter associated with
Expand All @@ -92,65 +96,71 @@ struct ParameterEventCallbackHandle
* You may also monitor for changes to parameters in other nodes by supplying the node
* name to add_parameter_callback:
*
* auto cb2 = [&node](const rclcpp::Parameter & p) {
* RCLCPP_INFO(
* node->get_logger(),
* "cb2: Received an update to parameter \"%s\" of type: %s: \"%s\"",
* p.get_name().c_str(),
* p.get_type_name().c_str(),
* p.as_string().c_str());
* };
* auto handle2 = param_handler->add_parameter_callback(
* "some_remote_param_name", cb2, "some_remote_node_name");
* ```cpp
* auto cb2 = [&node](const rclcpp::Parameter & p) {
* RCLCPP_INFO(
* node->get_logger(),
* "cb2: Received an update to parameter \"%s\" of type: %s: \"%s\"",
* p.get_name().c_str(),
* p.get_type_name().c_str(),
* p.as_string().c_str());
* };
* auto handle2 = param_handler->add_parameter_callback(
* "some_remote_param_name", cb2, "some_remote_node_name");
* ```
*
* In this case, the callback will be invoked whenever "some_remote_param_name" changes
* on remote node "some_remote_node_name".
*
* To remove a parameter callback, reset the callback handle smart pointer or call
* remove_parameter_callback, passing the handle returned from add_parameter_callback:
*
* param_handler->remove_parameter_callback(handle2);
* ```cpp
* param_handler->remove_parameter_callback(handle2);
* ```
*
* You can also monitor for *all* parameter changes, using add_parameter_event_callback.
* In this case, the callback will be invoked whenever any parameter changes in the system.
* You are likely interested in a subset of these parameter changes, so in the callback it
* is convenient to use a regular expression on the node names or namespaces of interest.
* For example:
*
* auto cb3 =
* [fqn, remote_param_name, &node](const rcl_interfaces::msg::ParameterEvent & event) {
* // Look for any updates to parameters in "/a_namespace" as well as any parameter changes
* // to our own node ("this_node")
* std::regex re("(/a_namespace/.*)|(/this_node)");
* if (regex_match(event.node, re)) {
* // Now that we know the event matches the regular expression we scanned for, we can
* // use 'get_parameter_from_event' to get a specific parameter name that we're looking for
* rclcpp::Parameter p;
* if (rclcpp::ParameterEventsSubscriber::get_parameter_from_event(
* event, p, remote_param_name, fqn))
* {
* RCLCPP_INFO(
* node->get_logger(),
* "cb3: Received an update to parameter \"%s\" of type: %s: \"%s\"",
* p.get_name().c_str(),
* p.get_type_name().c_str(),
* p.as_string().c_str());
* }
* ```cpp
* auto cb3 =
* [fqn, remote_param_name, &node](const rcl_interfaces::msg::ParameterEvent & event) {
* // Look for any updates to parameters in "/a_namespace" as well as any parameter changes
* // to our own node ("this_node")
* std::regex re("(/a_namespace/.*)|(/this_node)");
* if (regex_match(event.node, re)) {
* // Now that we know the event matches the regular expression we scanned for, we can
* // use 'get_parameter_from_event' to get a specific parameter name that we're looking for
* rclcpp::Parameter p;
* if (rclcpp::ParameterEventHandler::get_parameter_from_event(
* event, p, remote_param_name, fqn))
* {
* RCLCPP_INFO(
* node->get_logger(),
* "cb3: Received an update to parameter \"%s\" of type: %s: \"%s\"",
* p.get_name().c_str(),
* p.get_type_name().c_str(),
* p.as_string().c_str());
* }
*
* // You can also use 'get_parameter*s*_from_event' to enumerate all changes that came
* // in on this event
* auto params = rclcpp::ParameterEventsSubscriber::get_parameters_from_event(event);
* for (auto & p : params) {
* RCLCPP_INFO(
* node->get_logger(),
* "cb3: Received an update to parameter \"%s\" of type: %s: \"%s\"",
* p.get_name().c_str(),
* p.get_type_name().c_str(),
* p.value_to_string().c_str());
* }
* // You can also use 'get_parameter*s*_from_event' to enumerate all changes that came
* // in on this event
* auto params = rclcpp::ParameterEventHandler::get_parameters_from_event(event);
* for (auto & p : params) {
* RCLCPP_INFO(
* node->get_logger(),
* "cb3: Received an update to parameter \"%s\" of type: %s: \"%s\"",
* p.get_name().c_str(),
* p.get_type_name().c_str(),
* p.value_to_string().c_str());
* }
* };
* auto handle3 = param_handler->add_parameter_event_callback(cb3);
* }
* };
* auto handle3 = param_handler->add_parameter_event_callback(cb3);
* ```
*
* For both parameter callbacks and parameter event callbacks, when multiple callbacks are added,
* the callbacks are invoked last-in, first-called order (LIFO).
Expand All @@ -160,7 +170,9 @@ struct ParameterEventCallbackHandle
*
* To remove a parameter event callback, reset the callback smart pointer or use:
*
* param_handler->remove_event_parameter_callback(handle3);
* ```cpp
* param_handler->remove_event_parameter_callback(handle3);
* ```
*/
class ParameterEventHandler
{
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/parameter_value.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -359,7 +359,7 @@ class ParameterValue
/// Return the value of a parameter as a string
RCLCPP_PUBLIC
std::string
to_string(const ParameterValue & type);
to_string(const ParameterValue & value);

} // namespace rclcpp

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@ class Publisher : public PublisherBase
* the loaned message will be directly allocated in the middleware.
* If not, the message allocator of this rclcpp::Publisher instance is being used.
*
* With a call to \sa `publish` the LoanedMessage instance is being returned to the middleware
* With a call to `publish` the LoanedMessage instance is being returned to the middleware
* or free'd accordingly to the allocator.
* If the message is not being published but processed differently, the destructor of this
* class will either return the message to the middleware or deallocate it via the internal
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -172,12 +172,11 @@ class SubscriptionTopicStatistics
{
auto received_message_age = std::make_unique<ReceivedMessageAge>();
received_message_age->Start();
subscriber_statistics_collectors_.emplace_back(std::move(received_message_age));

auto received_message_period = std::make_unique<ReceivedMessagePeriod>();
received_message_period->Start();
{
std::lock_guard<std::mutex> lock(mutex_);
subscriber_statistics_collectors_.emplace_back(std::move(received_message_age));
subscriber_statistics_collectors_.emplace_back(std::move(received_message_period));
}

Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/waitable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
add_to_wait_set(rcl_wait_set_t & wait_set);
add_to_wait_set(rcl_wait_set_t & wait_set) = 0;

/// Check if the Waitable is ready.
/**
Expand All @@ -124,7 +124,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
bool
is_ready(const rcl_wait_set_t & wait_set);
is_ready(const rcl_wait_set_t & wait_set) = 0;

/// Take the data so that it can be consumed with `execute`.
/**
Expand Down Expand Up @@ -176,7 +176,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
std::shared_ptr<void>
take_data_by_entity_id(size_t id);
take_data_by_entity_id(size_t id) = 0;

/// Execute data that is passed in.
/**
Expand All @@ -203,7 +203,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
execute(const std::shared_ptr<void> & data);
execute(const std::shared_ptr<void> & data) = 0;

/// Exchange the "in use by wait set" state for this timer.
/**
Expand Down Expand Up @@ -246,7 +246,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
set_on_ready_callback(std::function<void(size_t, int)> callback);
set_on_ready_callback(std::function<void(size_t, int)> callback) = 0;

/// Unset any callback registered via set_on_ready_callback.
/**
Expand All @@ -256,7 +256,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
clear_on_ready_callback();
clear_on_ready_callback() = 0;

private:
std::atomic<bool> in_use_by_wait_set_{false};
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>rclcpp</name>
<version>28.3.2</version>
<version>28.3.3</version>
<description>The ROS client library in C++.</description>

<maintainer email="[email protected]">Ivan Paunovic</maintainer>
Expand Down
37 changes: 18 additions & 19 deletions rclcpp/src/rclcpp/context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,28 +212,27 @@ Context::init(
}
rcl_context_.reset(context, __delete_context);

if (init_options.auto_initialize_logging()) {
logging_mutex_ = get_global_logging_mutex();
std::lock_guard<std::recursive_mutex> guard(*logging_mutex_);
size_t & count = get_logging_reference_count();
if (0u == count) {
ret = rcl_logging_configure_with_output_handler(
&rcl_context_->global_arguments,
rcl_init_options_get_allocator(init_options.get_rcl_init_options()),
rclcpp_logging_output_handler);
if (RCL_RET_OK != ret) {
rcl_context_.reset();
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure logging");
try {
if (init_options.auto_initialize_logging()) {
logging_mutex_ = get_global_logging_mutex();
std::lock_guard<std::recursive_mutex> guard(*logging_mutex_);
size_t & count = get_logging_reference_count();
if (0u == count) {
ret = rcl_logging_configure_with_output_handler(
&rcl_context_->global_arguments,
rcl_init_options_get_allocator(init_options.get_rcl_init_options()),
rclcpp_logging_output_handler);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure logging");
}
} else {
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"logging was initialized more than once");
}
} else {
RCLCPP_WARN(
rclcpp::get_logger("rclcpp"),
"logging was initialized more than once");
++count;
}
++count;
}

try {
std::vector<std::string> unparsed_ros_arguments = detail::get_unparsed_ros_arguments(
argc, argv, &(rcl_context_->global_arguments), rcl_get_default_allocator());
if (!unparsed_ros_arguments.empty()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -359,6 +359,11 @@ EventsExecutor::refresh_current_collection(
// Acquire lock before modifying the current collection
std::lock_guard<std::mutex> guard(mutex_);

// Remove expired entities to ensure re-initialized objects
// are updated. This fixes issues with stale state entities.
// See: https://github.com/ros2/rclcpp/pull/2586
current_collection_.remove_expired_entities();

current_collection_.timers.update(
new_collection.timers,
[this](rclcpp::TimerBase::SharedPtr timer) {timers_manager_->add_timer(timer);},
Expand Down
Loading

0 comments on commit 1b5de29

Please sign in to comment.