Skip to content

Commit 447ba81

Browse files
authored
Merge branch 'rolling' into revert-1956-revert-1874-hliberacki/timeout
2 parents 0f90756 + ab71df3 commit 447ba81

File tree

143 files changed

+5584
-1284
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

143 files changed

+5584
-1284
lines changed
Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
name: Mirror rolling to master
2+
3+
on:
4+
push:
5+
branches: [ rolling ]
6+
7+
jobs:
8+
mirror-to-master:
9+
runs-on: ubuntu-latest
10+
steps:
11+
- uses: zofrex/mirror-branch@v1
12+
with:
13+
target-branch: master

CODEOWNERS

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,2 @@
1+
# This file was generated by https://github.com/audrow/update-ros2-repos
2+
* @ivanpauno @hidmic @wjwwood

README.md

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,8 @@ rclcpp provides the standard C++ API for interacting with ROS 2.
88

99
`#include "rclcpp/rclcpp.hpp"` allows use of the most common elements of the ROS 2 system.
1010

11-
Visit the [rclcpp API documentation](http://docs.ros2.org/latest/api/rclcpp/) for a complete list of its main components.
11+
The link to the latest API documentation can be found on the rclcpp package info page, at the [ROS Index](https://index.ros.org/p/rclcpp/).
12+
1213

1314
### Examples
1415

rclcpp/CHANGELOG.rst

Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,65 @@
22
Changelog for package rclcpp
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
18.0.0 (2022-12-29)
6+
-------------------
7+
* Implement Unified Node Interface (NodeInterfaces class) (`#2041 <https://github.com/ros2/rclcpp/issues/2041>`_)
8+
* Do not throw exception if trying to dequeue an empty intra-process buffer (`#2061 <https://github.com/ros2/rclcpp/issues/2061>`_)
9+
* Move event callback binding to PublisherBase and SubscriptionBase (`#2066 <https://github.com/ros2/rclcpp/issues/2066>`_)
10+
* Implement validity checks for rclcpp::Clock (`#2040 <https://github.com/ros2/rclcpp/issues/2040>`_)
11+
* Explicitly set callback type (`#2059 <https://github.com/ros2/rclcpp/issues/2059>`_)
12+
* Fix logging macros to build with msvc and cpp20 (`#2063 <https://github.com/ros2/rclcpp/issues/2063>`_)
13+
* Add clock type to node_options (`#1982 <https://github.com/ros2/rclcpp/issues/1982>`_)
14+
* Fix nullptr dereference in prune_requests_older_than (`#2008 <https://github.com/ros2/rclcpp/issues/2008>`_)
15+
* Remove templating on to_rcl_subscription_options (`#2056 <https://github.com/ros2/rclcpp/issues/2056>`_)
16+
* Fix SharedFuture from async_send_request never becoming valid (`#2044 <https://github.com/ros2/rclcpp/issues/2044>`_)
17+
* Add in a warning for a KeepLast depth of 0. (`#2048 <https://github.com/ros2/rclcpp/issues/2048>`_)
18+
* Mark rclcpp::Clock::now() as const (`#2050 <https://github.com/ros2/rclcpp/issues/2050>`_)
19+
* Fix a case that did not throw ParameterUninitializedException (`#2036 <https://github.com/ros2/rclcpp/issues/2036>`_)
20+
* Update maintainers (`#2043 <https://github.com/ros2/rclcpp/issues/2043>`_)
21+
* Contributors: Alberto Soragna, Audrow Nash, Chen Lihui, Chris Lalancette, Jeffery Hsu, Lei Liu, Mateusz Szczygielski, Shane Loretz, andrei, mauropasse, methylDragon
22+
23+
17.1.0 (2022-11-02)
24+
-------------------
25+
* MultiThreadExecutor number of threads is at least 2+ in default. (`#2032 <https://github.com/ros2/rclcpp/issues/2032>`_)
26+
* Fix bug that a callback not reached (`#1640 <https://github.com/ros2/rclcpp/issues/1640>`_)
27+
* Set the minimum number of threads of the Multithreaded executor to 2 (`#2030 <https://github.com/ros2/rclcpp/issues/2030>`_)
28+
* check thread whether joinable before join (`#2019 <https://github.com/ros2/rclcpp/issues/2019>`_)
29+
* Set cpplint test timeout to 3 minutes (`#2022 <https://github.com/ros2/rclcpp/issues/2022>`_)
30+
* Make sure to include-what-you-use in the node_interfaces. (`#2018 <https://github.com/ros2/rclcpp/issues/2018>`_)
31+
* Do not clear entities callbacks on destruction (`#2002 <https://github.com/ros2/rclcpp/issues/2002>`_)
32+
* fix mismatched issue if using zero_allocate (`#1995 <https://github.com/ros2/rclcpp/issues/1995>`_)
33+
* Contributors: Alexis Paques, Chen Lihui, Chris Lalancette, Cristóbal Arroyo, Tomoya Fujita, mauropasse, uupks
34+
35+
17.0.0 (2022-09-13)
36+
-------------------
37+
* Make ParameterService and Sync/AsyncParameterClient accept rclcpp::QoS (`#1978 <https://github.com/ros2/rclcpp/issues/1978>`_)
38+
* support regex match for parameter client (`#1992 <https://github.com/ros2/rclcpp/issues/1992>`_)
39+
* operator+= and operator-= for Duration (`#1988 <https://github.com/ros2/rclcpp/issues/1988>`_)
40+
* Revert "Revert "Add a create_timer method to Node and `LifecycleNode` classes (`#1975 <https://github.com/ros2/rclcpp/issues/1975>`_)" (`#2009 <https://github.com/ros2/rclcpp/issues/2009>`_) (`#2010 <https://github.com/ros2/rclcpp/issues/2010>`_)
41+
* force compiler warning if callback handles not captured (`#2000 <https://github.com/ros2/rclcpp/issues/2000>`_)
42+
* Revert "Add a `create_timer` method to `Node` and `LifecycleNode` classes (`#1975 <https://github.com/ros2/rclcpp/issues/1975>`_)" (`#2009 <https://github.com/ros2/rclcpp/issues/2009>`_)
43+
* Add a `create_timer` method to `Node` and `LifecycleNode` classes (`#1975 <https://github.com/ros2/rclcpp/issues/1975>`_)
44+
* [docs] add note about callback lifetime for {on, post}_set_parameter_callback (`#1981 <https://github.com/ros2/rclcpp/issues/1981>`_)
45+
* fix memory leak (`#1994 <https://github.com/ros2/rclcpp/issues/1994>`_)
46+
* Support pre-set and post-set parameter callbacks in addition to on-set-parameter-callback. (`#1947 <https://github.com/ros2/rclcpp/issues/1947>`_)
47+
* Make create_service accept rclcpp::QoS (`#1969 <https://github.com/ros2/rclcpp/issues/1969>`_)
48+
* Make create_client accept rclcpp::QoS (`#1964 <https://github.com/ros2/rclcpp/issues/1964>`_)
49+
* Fix the documentation for rclcpp::ok to be accurate. (`#1965 <https://github.com/ros2/rclcpp/issues/1965>`_)
50+
* use regex for wildcard matching (`#1839 <https://github.com/ros2/rclcpp/issues/1839>`_)
51+
* Revert "Introduce executors new spin_for method, replace spin_until_future_complete with spin_until_complete. (`#1821 <https://github.com/ros2/rclcpp/issues/1821>`_) (`#1874 <https://github.com/ros2/rclcpp/issues/1874>`_)" (`#1956 <https://github.com/ros2/rclcpp/issues/1956>`_)
52+
* Introduce executors new spin_for method, replace spin_until_future_complete with spin_until_complete. (`#1821 <https://github.com/ros2/rclcpp/issues/1821>`_) (`#1874 <https://github.com/ros2/rclcpp/issues/1874>`_)
53+
* test adjustment for LoanedMessage. (`#1951 <https://github.com/ros2/rclcpp/issues/1951>`_)
54+
* fix virtual dispatch issues identified by clang-tidy (`#1816 <https://github.com/ros2/rclcpp/issues/1816>`_)
55+
* Remove unused on_parameters_set_callback\_ (`#1945 <https://github.com/ros2/rclcpp/issues/1945>`_)
56+
* Fix subscription.is_serialized() for callbacks with message info (`#1950 <https://github.com/ros2/rclcpp/issues/1950>`_)
57+
* wait for subscriptions on another thread. (`#1940 <https://github.com/ros2/rclcpp/issues/1940>`_)
58+
* Fix documentation of `RCLCPP\_[INFO,WARN,...]` (`#1943 <https://github.com/ros2/rclcpp/issues/1943>`_)
59+
* Always trigger guard condition waitset (`#1923 <https://github.com/ros2/rclcpp/issues/1923>`_)
60+
* Add statistics for handle_loaned_message (`#1927 <https://github.com/ros2/rclcpp/issues/1927>`_)
61+
* Drop wrong template specialization (`#1926 <https://github.com/ros2/rclcpp/issues/1926>`_)
62+
* Contributors: Alberto Soragna, Andrew Symington, Barry Xu, Brian, Chen Lihui, Chris Lalancette, Daniel Reuter, Deepanshu Bansal, Hubert Liberacki, Ivan Santiago Paunovic, Jochen Sprickerhof, Nikolai Morin, Shane Loretz, Tomoya Fujita, Tyler Weaver, William Woodall, schrodinbug
63+
564
16.2.0 (2022-05-03)
665
-------------------
766
* Update get_parameter_from_event to follow the function description (`#1922 <https://github.com/ros2/rclcpp/issues/1922>`_)

rclcpp/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -259,4 +259,8 @@ if(TEST cppcheck)
259259
set_tests_properties(cppcheck PROPERTIES TIMEOUT 500)
260260
endif()
261261

262+
if(TEST cpplint)
263+
set_tests_properties(cpplint PROPERTIES TIMEOUT 180)
264+
endif()
265+
262266
ament_generate_version_header(${PROJECT_NAME})
164 KB
Loading
Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
# Proposed node parameters callback Design
2+
3+
## Introduction:
4+
5+
The original requirement came in **gazebo_ros_pkgs** for setting individual wheel slip parameters based on global wheel slip value [link to original issue](https://github.com/ros-simulation/gazebo_ros_pkgs/pull/1365).
6+
7+
The main requirement is to set one or more parameters after another parameter is set successfully.
8+
9+
Additionally, it would be nice if users could be notified locally (via a callback) when parameters have been set successfully (i.e. post validation).
10+
11+
Related discussion can be found in [#609](https://github.com/ros2/rclcpp/issues/609) [#1789](https://github.com/ros2/rclcpp/pull/1789)
12+
13+
With the current parameters API, the `add_on_set_parameters_callback` is intended for validation of parameter values before they are set, it should **not** cause any side-effects.
14+
15+
There is also the `ParameterEventHandler` that publishes changes to node parameters on `/parameter_events` topic for external nodes to see. Though the node could subscribe to the `/parameter_events` topic to be notified of changes to its own parameters, it is less than ideal since there is a delay caused by waiting for an executor to process the callback.
16+
17+
We propose adding a `PostSetParametersCallbackHandle` for successful parameter set similar to `OnSetParametersCallbackHandle` for parameter validation. Also, we propose adding a `PreSetParametersCallbackHandle` useful for modifying list of parameters being set.
18+
19+
The validation callback is often abused to trigger side effects in the code, for instance updating class attributes even before a parameter has been set successfully. Instead of relying on the `/parameter_events` topic to be notified of parameter changes, users can register a callback with a new API, `add_post_set_parameters_callback`.
20+
21+
It is possible to use the proposed `add_post_set_parameters_callback` for setting additional parameters, but this might result in infinite recursion and does not allow those additional parameters to be set atomically with the original parameter(s) changed.
22+
To workaround these issues, we propose adding a "pre set" callback type that can be registered with `add_pre_set_parameters_callback`, which will be triggered before the validation callbacks and can be used to modify the parameter list.
23+
24+
![Desgin API](https://github.com/ros2/rclcpp/blob/deepanshu/local-param-changed-callback-support/rclcpp/doc/param_callback_design.png?raw=true)
25+
26+
## Alternatives
27+
28+
* Users could call `set_parameter` while processing a message from the `/parameter_events` topic, however, there is extra overhead in having to create subscription (as noted earlier).
29+
* Users could call `set_parameter` inside the "on set" parameters callback, however it is not well-defined how side-effects should handle cases where parameter validation fails.

rclcpp/include/rclcpp/allocator/allocator_common.hpp

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef RCLCPP__ALLOCATOR__ALLOCATOR_COMMON_HPP_
1616
#define RCLCPP__ALLOCATOR__ALLOCATOR_COMMON_HPP_
1717

18+
#include <cstring>
1819
#include <memory>
1920

2021
#include "rcl/allocator.h"
@@ -39,6 +40,22 @@ void * retyped_allocate(size_t size, void * untyped_allocator)
3940
return std::allocator_traits<Alloc>::allocate(*typed_allocator, size);
4041
}
4142

43+
template<typename Alloc>
44+
void * retyped_zero_allocate(size_t number_of_elem, size_t size_of_elem, void * untyped_allocator)
45+
{
46+
auto typed_allocator = static_cast<Alloc *>(untyped_allocator);
47+
if (!typed_allocator) {
48+
throw std::runtime_error("Received incorrect allocator type");
49+
}
50+
size_t size = number_of_elem * size_of_elem;
51+
void * allocated_memory =
52+
std::allocator_traits<Alloc>::allocate(*typed_allocator, size);
53+
if (allocated_memory) {
54+
std::memset(allocated_memory, 0, size);
55+
}
56+
return allocated_memory;
57+
}
58+
4259
template<typename T, typename Alloc>
4360
void retyped_deallocate(void * untyped_pointer, void * untyped_allocator)
4461
{
@@ -73,6 +90,7 @@ rcl_allocator_t get_rcl_allocator(Alloc & allocator)
7390
rcl_allocator_t rcl_allocator = rcl_get_default_allocator();
7491
#ifndef _WIN32
7592
rcl_allocator.allocate = &retyped_allocate<Alloc>;
93+
rcl_allocator.zero_allocate = &retyped_zero_allocate<Alloc>;
7694
rcl_allocator.deallocate = &retyped_deallocate<T, Alloc>;
7795
rcl_allocator.reallocate = &retyped_reallocate<T, Alloc>;
7896
rcl_allocator.state = &allocator;

rclcpp/include/rclcpp/callback_group.hpp

Lines changed: 21 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,11 +16,14 @@
1616
#define RCLCPP__CALLBACK_GROUP_HPP_
1717

1818
#include <atomic>
19+
#include <functional>
20+
#include <memory>
1921
#include <mutex>
20-
#include <string>
2122
#include <vector>
2223

2324
#include "rclcpp/client.hpp"
25+
#include "rclcpp/context.hpp"
26+
#include "rclcpp/guard_condition.hpp"
2427
#include "rclcpp/publisher_base.hpp"
2528
#include "rclcpp/service.hpp"
2629
#include "rclcpp/subscription_base.hpp"
@@ -95,6 +98,10 @@ class CallbackGroup
9598
CallbackGroupType group_type,
9699
bool automatically_add_to_executor_with_node = true);
97100

101+
/// Default destructor.
102+
RCLCPP_PUBLIC
103+
~CallbackGroup();
104+
98105
template<typename Function>
99106
rclcpp::SubscriptionBase::SharedPtr
100107
find_subscription_ptrs_if(Function func) const
@@ -171,6 +178,16 @@ class CallbackGroup
171178
bool
172179
automatically_add_to_executor_with_node() const;
173180

181+
/// Defer creating the notify guard condition and return it.
182+
RCLCPP_PUBLIC
183+
rclcpp::GuardCondition::SharedPtr
184+
get_notify_guard_condition(const rclcpp::Context::SharedPtr context_ptr);
185+
186+
/// Trigger the notify guard condition.
187+
RCLCPP_PUBLIC
188+
void
189+
trigger_notify_guard_condition();
190+
174191
protected:
175192
RCLCPP_DISABLE_COPY(CallbackGroup)
176193

@@ -213,6 +230,9 @@ class CallbackGroup
213230
std::vector<rclcpp::Waitable::WeakPtr> waitable_ptrs_;
214231
std::atomic_bool can_be_taken_from_;
215232
const bool automatically_add_to_executor_with_node_;
233+
// defer the creation of the guard condition
234+
std::shared_ptr<rclcpp::GuardCondition> notify_guard_condition_ = nullptr;
235+
std::recursive_mutex notify_guard_condition_mutex_;
216236

217237
private:
218238
template<typename TypeT, typename Function>

rclcpp/include/rclcpp/client.hpp

Lines changed: 11 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ class ClientBase
130130
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph);
131131

132132
RCLCPP_PUBLIC
133-
virtual ~ClientBase();
133+
virtual ~ClientBase() = default;
134134

135135
/// Take the next response for this client as a type erased pointer.
136136
/**
@@ -312,15 +312,16 @@ class ClientBase
312312
// This two-step setting, prevents a gap where the old std::function has
313313
// been replaced but the middleware hasn't been told about the new one yet.
314314
set_on_new_response_callback(
315-
rclcpp::detail::cpp_callback_trampoline<const void *, size_t>,
315+
rclcpp::detail::cpp_callback_trampoline<decltype(new_callback), const void *, size_t>,
316316
static_cast<const void *>(&new_callback));
317317

318318
// Store the std::function to keep it in scope, also overwrites the existing one.
319319
on_new_response_callback_ = new_callback;
320320

321321
// Set it again, now using the permanent storage.
322322
set_on_new_response_callback(
323-
rclcpp::detail::cpp_callback_trampoline<const void *, size_t>,
323+
rclcpp::detail::cpp_callback_trampoline<
324+
decltype(on_new_response_callback_), const void *, size_t>,
324325
static_cast<const void *>(&on_new_response_callback_));
325326
}
326327

@@ -769,7 +770,9 @@ class Client : public ClientBase
769770
auto old_size = pending_requests_.size();
770771
for (auto it = pending_requests_.begin(), last = pending_requests_.end(); it != last; ) {
771772
if (it->second.first < time_point) {
772-
pruned_requests->push_back(it->first);
773+
if (pruned_requests) {
774+
pruned_requests->push_back(it->first);
775+
}
773776
it = pending_requests_.erase(it);
774777
} else {
775778
++it;
@@ -792,16 +795,14 @@ class Client : public ClientBase
792795
async_send_request_impl(const Request & request, CallbackInfoVariant value)
793796
{
794797
int64_t sequence_number;
798+
std::lock_guard<std::mutex> lock(pending_requests_mutex_);
795799
rcl_ret_t ret = rcl_send_request(get_client_handle().get(), &request, &sequence_number);
796800
if (RCL_RET_OK != ret) {
797801
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to send request");
798802
}
799-
{
800-
std::lock_guard<std::mutex> lock(pending_requests_mutex_);
801-
pending_requests_.try_emplace(
802-
sequence_number,
803-
std::make_pair(std::chrono::system_clock::now(), std::move(value)));
804-
}
803+
pending_requests_.try_emplace(
804+
sequence_number,
805+
std::make_pair(std::chrono::system_clock::now(), std::move(value)));
805806
return sequence_number;
806807
}
807808

0 commit comments

Comments
 (0)