Skip to content

Commit

Permalink
Merge branch 'rolling' into revert-1956-revert-1874-hliberacki/timeout
Browse files Browse the repository at this point in the history
Signed-off-by: Tomoya Fujita <[email protected]>
  • Loading branch information
fujitatomoya committed Jan 23, 2023
2 parents 0f90756 + ab71df3 commit cde7a67
Show file tree
Hide file tree
Showing 143 changed files with 5,584 additions and 1,284 deletions.
13 changes: 13 additions & 0 deletions .github/workflows/mirror-rolling-to-master.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
name: Mirror rolling to master

on:
push:
branches: [ rolling ]

jobs:
mirror-to-master:
runs-on: ubuntu-latest
steps:
- uses: zofrex/mirror-branch@v1
with:
target-branch: master
2 changes: 2 additions & 0 deletions CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
# This file was generated by https://github.com/audrow/update-ros2-repos
* @ivanpauno @hidmic @wjwwood
3 changes: 2 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@ rclcpp provides the standard C++ API for interacting with ROS 2.

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

Visit the [rclcpp API documentation](http://docs.ros2.org/latest/api/rclcpp/) for a complete list of its main components.
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/).


### Examples

Expand Down
59 changes: 59 additions & 0 deletions rclcpp/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,65 @@
Changelog for package rclcpp
^^^^^^^^^^^^^^^^^^^^^^^^^^^^

18.0.0 (2022-12-29)
-------------------
* Implement Unified Node Interface (NodeInterfaces class) (`#2041 <https://github.com/ros2/rclcpp/issues/2041>`_)
* Do not throw exception if trying to dequeue an empty intra-process buffer (`#2061 <https://github.com/ros2/rclcpp/issues/2061>`_)
* Move event callback binding to PublisherBase and SubscriptionBase (`#2066 <https://github.com/ros2/rclcpp/issues/2066>`_)
* Implement validity checks for rclcpp::Clock (`#2040 <https://github.com/ros2/rclcpp/issues/2040>`_)
* Explicitly set callback type (`#2059 <https://github.com/ros2/rclcpp/issues/2059>`_)
* Fix logging macros to build with msvc and cpp20 (`#2063 <https://github.com/ros2/rclcpp/issues/2063>`_)
* Add clock type to node_options (`#1982 <https://github.com/ros2/rclcpp/issues/1982>`_)
* Fix nullptr dereference in prune_requests_older_than (`#2008 <https://github.com/ros2/rclcpp/issues/2008>`_)
* Remove templating on to_rcl_subscription_options (`#2056 <https://github.com/ros2/rclcpp/issues/2056>`_)
* Fix SharedFuture from async_send_request never becoming valid (`#2044 <https://github.com/ros2/rclcpp/issues/2044>`_)
* Add in a warning for a KeepLast depth of 0. (`#2048 <https://github.com/ros2/rclcpp/issues/2048>`_)
* Mark rclcpp::Clock::now() as const (`#2050 <https://github.com/ros2/rclcpp/issues/2050>`_)
* Fix a case that did not throw ParameterUninitializedException (`#2036 <https://github.com/ros2/rclcpp/issues/2036>`_)
* Update maintainers (`#2043 <https://github.com/ros2/rclcpp/issues/2043>`_)
* Contributors: Alberto Soragna, Audrow Nash, Chen Lihui, Chris Lalancette, Jeffery Hsu, Lei Liu, Mateusz Szczygielski, Shane Loretz, andrei, mauropasse, methylDragon

17.1.0 (2022-11-02)
-------------------
* MultiThreadExecutor number of threads is at least 2+ in default. (`#2032 <https://github.com/ros2/rclcpp/issues/2032>`_)
* Fix bug that a callback not reached (`#1640 <https://github.com/ros2/rclcpp/issues/1640>`_)
* Set the minimum number of threads of the Multithreaded executor to 2 (`#2030 <https://github.com/ros2/rclcpp/issues/2030>`_)
* check thread whether joinable before join (`#2019 <https://github.com/ros2/rclcpp/issues/2019>`_)
* Set cpplint test timeout to 3 minutes (`#2022 <https://github.com/ros2/rclcpp/issues/2022>`_)
* Make sure to include-what-you-use in the node_interfaces. (`#2018 <https://github.com/ros2/rclcpp/issues/2018>`_)
* Do not clear entities callbacks on destruction (`#2002 <https://github.com/ros2/rclcpp/issues/2002>`_)
* fix mismatched issue if using zero_allocate (`#1995 <https://github.com/ros2/rclcpp/issues/1995>`_)
* Contributors: Alexis Paques, Chen Lihui, Chris Lalancette, Cristóbal Arroyo, Tomoya Fujita, mauropasse, uupks

17.0.0 (2022-09-13)
-------------------
* Make ParameterService and Sync/AsyncParameterClient accept rclcpp::QoS (`#1978 <https://github.com/ros2/rclcpp/issues/1978>`_)
* support regex match for parameter client (`#1992 <https://github.com/ros2/rclcpp/issues/1992>`_)
* operator+= and operator-= for Duration (`#1988 <https://github.com/ros2/rclcpp/issues/1988>`_)
* 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>`_)
* force compiler warning if callback handles not captured (`#2000 <https://github.com/ros2/rclcpp/issues/2000>`_)
* 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>`_)
* Add a `create_timer` method to `Node` and `LifecycleNode` classes (`#1975 <https://github.com/ros2/rclcpp/issues/1975>`_)
* [docs] add note about callback lifetime for {on, post}_set_parameter_callback (`#1981 <https://github.com/ros2/rclcpp/issues/1981>`_)
* fix memory leak (`#1994 <https://github.com/ros2/rclcpp/issues/1994>`_)
* Support pre-set and post-set parameter callbacks in addition to on-set-parameter-callback. (`#1947 <https://github.com/ros2/rclcpp/issues/1947>`_)
* Make create_service accept rclcpp::QoS (`#1969 <https://github.com/ros2/rclcpp/issues/1969>`_)
* Make create_client accept rclcpp::QoS (`#1964 <https://github.com/ros2/rclcpp/issues/1964>`_)
* Fix the documentation for rclcpp::ok to be accurate. (`#1965 <https://github.com/ros2/rclcpp/issues/1965>`_)
* use regex for wildcard matching (`#1839 <https://github.com/ros2/rclcpp/issues/1839>`_)
* 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>`_)
* 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>`_)
* test adjustment for LoanedMessage. (`#1951 <https://github.com/ros2/rclcpp/issues/1951>`_)
* fix virtual dispatch issues identified by clang-tidy (`#1816 <https://github.com/ros2/rclcpp/issues/1816>`_)
* Remove unused on_parameters_set_callback\_ (`#1945 <https://github.com/ros2/rclcpp/issues/1945>`_)
* Fix subscription.is_serialized() for callbacks with message info (`#1950 <https://github.com/ros2/rclcpp/issues/1950>`_)
* wait for subscriptions on another thread. (`#1940 <https://github.com/ros2/rclcpp/issues/1940>`_)
* Fix documentation of `RCLCPP\_[INFO,WARN,...]` (`#1943 <https://github.com/ros2/rclcpp/issues/1943>`_)
* Always trigger guard condition waitset (`#1923 <https://github.com/ros2/rclcpp/issues/1923>`_)
* Add statistics for handle_loaned_message (`#1927 <https://github.com/ros2/rclcpp/issues/1927>`_)
* Drop wrong template specialization (`#1926 <https://github.com/ros2/rclcpp/issues/1926>`_)
* 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

16.2.0 (2022-05-03)
-------------------
* Update get_parameter_from_event to follow the function description (`#1922 <https://github.com/ros2/rclcpp/issues/1922>`_)
Expand Down
4 changes: 4 additions & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -259,4 +259,8 @@ if(TEST cppcheck)
set_tests_properties(cppcheck PROPERTIES TIMEOUT 500)
endif()

if(TEST cpplint)
set_tests_properties(cpplint PROPERTIES TIMEOUT 180)
endif()

ament_generate_version_header(${PROJECT_NAME})
Binary file added rclcpp/doc/param_callback_design.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
29 changes: 29 additions & 0 deletions rclcpp/doc/proposed_node_parameter_callbacks.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
# Proposed node parameters callback Design

## Introduction:

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).

The main requirement is to set one or more parameters after another parameter is set successfully.

Additionally, it would be nice if users could be notified locally (via a callback) when parameters have been set successfully (i.e. post validation).

Related discussion can be found in [#609](https://github.com/ros2/rclcpp/issues/609) [#1789](https://github.com/ros2/rclcpp/pull/1789)

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.

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.

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.

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`.

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.
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.

![Desgin API](https://github.com/ros2/rclcpp/blob/deepanshu/local-param-changed-callback-support/rclcpp/doc/param_callback_design.png?raw=true)

## Alternatives

* 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).
* 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.
18 changes: 18 additions & 0 deletions rclcpp/include/rclcpp/allocator/allocator_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef RCLCPP__ALLOCATOR__ALLOCATOR_COMMON_HPP_
#define RCLCPP__ALLOCATOR__ALLOCATOR_COMMON_HPP_

#include <cstring>
#include <memory>

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

template<typename Alloc>
void * retyped_zero_allocate(size_t number_of_elem, size_t size_of_elem, void * untyped_allocator)
{
auto typed_allocator = static_cast<Alloc *>(untyped_allocator);
if (!typed_allocator) {
throw std::runtime_error("Received incorrect allocator type");
}
size_t size = number_of_elem * size_of_elem;
void * allocated_memory =
std::allocator_traits<Alloc>::allocate(*typed_allocator, size);
if (allocated_memory) {
std::memset(allocated_memory, 0, size);
}
return allocated_memory;
}

template<typename T, typename Alloc>
void retyped_deallocate(void * untyped_pointer, void * untyped_allocator)
{
Expand Down Expand Up @@ -73,6 +90,7 @@ rcl_allocator_t get_rcl_allocator(Alloc & allocator)
rcl_allocator_t rcl_allocator = rcl_get_default_allocator();
#ifndef _WIN32
rcl_allocator.allocate = &retyped_allocate<Alloc>;
rcl_allocator.zero_allocate = &retyped_zero_allocate<Alloc>;
rcl_allocator.deallocate = &retyped_deallocate<T, Alloc>;
rcl_allocator.reallocate = &retyped_reallocate<T, Alloc>;
rcl_allocator.state = &allocator;
Expand Down
22 changes: 21 additions & 1 deletion rclcpp/include/rclcpp/callback_group.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,14 @@
#define RCLCPP__CALLBACK_GROUP_HPP_

#include <atomic>
#include <functional>
#include <memory>
#include <mutex>
#include <string>
#include <vector>

#include "rclcpp/client.hpp"
#include "rclcpp/context.hpp"
#include "rclcpp/guard_condition.hpp"
#include "rclcpp/publisher_base.hpp"
#include "rclcpp/service.hpp"
#include "rclcpp/subscription_base.hpp"
Expand Down Expand Up @@ -95,6 +98,10 @@ class CallbackGroup
CallbackGroupType group_type,
bool automatically_add_to_executor_with_node = true);

/// Default destructor.
RCLCPP_PUBLIC
~CallbackGroup();

template<typename Function>
rclcpp::SubscriptionBase::SharedPtr
find_subscription_ptrs_if(Function func) const
Expand Down Expand Up @@ -171,6 +178,16 @@ class CallbackGroup
bool
automatically_add_to_executor_with_node() const;

/// Defer creating the notify guard condition and return it.
RCLCPP_PUBLIC
rclcpp::GuardCondition::SharedPtr
get_notify_guard_condition(const rclcpp::Context::SharedPtr context_ptr);

/// Trigger the notify guard condition.
RCLCPP_PUBLIC
void
trigger_notify_guard_condition();

protected:
RCLCPP_DISABLE_COPY(CallbackGroup)

Expand Down Expand Up @@ -213,6 +230,9 @@ class CallbackGroup
std::vector<rclcpp::Waitable::WeakPtr> waitable_ptrs_;
std::atomic_bool can_be_taken_from_;
const bool automatically_add_to_executor_with_node_;
// defer the creation of the guard condition
std::shared_ptr<rclcpp::GuardCondition> notify_guard_condition_ = nullptr;
std::recursive_mutex notify_guard_condition_mutex_;

private:
template<typename TypeT, typename Function>
Expand Down
21 changes: 11 additions & 10 deletions rclcpp/include/rclcpp/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ class ClientBase
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph);

RCLCPP_PUBLIC
virtual ~ClientBase();
virtual ~ClientBase() = default;

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

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

// Set it again, now using the permanent storage.
set_on_new_response_callback(
rclcpp::detail::cpp_callback_trampoline<const void *, size_t>,
rclcpp::detail::cpp_callback_trampoline<
decltype(on_new_response_callback_), const void *, size_t>,
static_cast<const void *>(&on_new_response_callback_));
}

Expand Down Expand Up @@ -769,7 +770,9 @@ class Client : public ClientBase
auto old_size = pending_requests_.size();
for (auto it = pending_requests_.begin(), last = pending_requests_.end(); it != last; ) {
if (it->second.first < time_point) {
pruned_requests->push_back(it->first);
if (pruned_requests) {
pruned_requests->push_back(it->first);
}
it = pending_requests_.erase(it);
} else {
++it;
Expand All @@ -792,16 +795,14 @@ class Client : public ClientBase
async_send_request_impl(const Request & request, CallbackInfoVariant value)
{
int64_t sequence_number;
std::lock_guard<std::mutex> lock(pending_requests_mutex_);
rcl_ret_t ret = rcl_send_request(get_client_handle().get(), &request, &sequence_number);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to send request");
}
{
std::lock_guard<std::mutex> lock(pending_requests_mutex_);
pending_requests_.try_emplace(
sequence_number,
std::make_pair(std::chrono::system_clock::now(), std::move(value)));
}
pending_requests_.try_emplace(
sequence_number,
std::make_pair(std::chrono::system_clock::now(), std::move(value)));
return sequence_number;
}

Expand Down
47 changes: 46 additions & 1 deletion rclcpp/include/rclcpp/clock.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class Clock
*/
RCLCPP_PUBLIC
Time
now();
now() const;

/**
* Sleep until a specified Time, according to clock type.
Expand Down Expand Up @@ -137,6 +137,51 @@ class Clock
Duration rel_time,
Context::SharedPtr context = contexts::get_global_default_context());

/**
* Check if the clock is started.
*
* A started clock is a clock that reflects non-zero time.
* Typically a clock will be unstarted if it is using RCL_ROS_TIME with ROS time and
* nothing has been published on the clock topic yet.
*
* \return true if clock is started
* \throws std::runtime_error if the clock is not rcl_clock_valid
*/
RCLCPP_PUBLIC
bool
started();

/**
* Wait until clock to start.
*
* \rclcpp::Clock::started
* \param context the context to wait in
* \return true if clock was already started or became started
* \throws std::runtime_error if the context is invalid or clock is not rcl_clock_valid
*/
RCLCPP_PUBLIC
bool
wait_until_started(Context::SharedPtr context = contexts::get_global_default_context());

/**
* Wait for clock to start, with timeout.
*
* The timeout is waited in steady time.
*
* \rclcpp::Clock::started
* \param timeout the maximum time to wait for.
* \param context the context to wait in.
* \param wait_tick_ns the time to wait between each iteration of the wait loop (in nanoseconds).
* \return true if clock was or became valid
* \throws std::runtime_error if the context is invalid or clock is not rcl_clock_valid
*/
RCLCPP_PUBLIC
bool
wait_until_started(
const rclcpp::Duration & timeout,
Context::SharedPtr context = contexts::get_global_default_context(),
const rclcpp::Duration & wait_tick_ns = rclcpp::Duration(0, static_cast<uint32_t>(1e7)));

/**
* Returns the clock of the type `RCL_ROS_TIME` is active.
*
Expand Down
8 changes: 5 additions & 3 deletions rclcpp/include/rclcpp/context.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -398,20 +398,22 @@ class Context : public std::enable_shared_from_this<Context>

using ShutdownCallback = ShutdownCallbackHandle::ShutdownCallbackType;

template<ShutdownType shutdown_type>
RCLCPP_LOCAL
ShutdownCallbackHandle
add_shutdown_callback(
ShutdownType shutdown_type,
ShutdownCallback callback);

template<ShutdownType shutdown_type>
RCLCPP_LOCAL
bool
remove_shutdown_callback(
ShutdownType shutdown_type,
const ShutdownCallbackHandle & callback_handle);

template<ShutdownType shutdown_type>
RCLCPP_LOCAL
std::vector<rclcpp::Context::ShutdownCallback>
get_shutdown_callback(ShutdownType shutdown_type) const;
get_shutdown_callback() const;
};

/// Return a copy of the list of context shared pointers.
Expand Down
Loading

0 comments on commit cde7a67

Please sign in to comment.