Skip to content

Commit

Permalink
Merge remote-tracking branch 'remotes/origin/rolling' into topic-rosi…
Browse files Browse the repository at this point in the history
…dl-typesupport-helper
  • Loading branch information
Chen Lihui committed Nov 6, 2023
2 parents 100ae1d + d407a5e commit 8843d54
Show file tree
Hide file tree
Showing 105 changed files with 2,418 additions and 1,118 deletions.
66 changes: 66 additions & 0 deletions rclcpp/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,72 @@
Changelog for package rclcpp
^^^^^^^^^^^^^^^^^^^^^^^^^^^^

23.2.0 (2023-10-09)
-------------------
* add clients & services count (`#2072 <https://github.com/ros2/rclcpp/issues/2072>`_)
* remove invalid sized allocation test for SerializedMessage. (`#2330 <https://github.com/ros2/rclcpp/issues/2330>`_)
* Adding API to copy all parameters from one node to another (`#2304 <https://github.com/ros2/rclcpp/issues/2304>`_)
* Contributors: Minju, Lee, Steve Macenski, Tomoya Fujita

23.1.0 (2023-10-04)
-------------------
* Add locking to protect the TimeSource::NodeState::node_base\_ (`#2320 <https://github.com/ros2/rclcpp/issues/2320>`_)
* Update SignalHandler get_global_signal_handler to avoid complex types in static memory (`#2316 <https://github.com/ros2/rclcpp/issues/2316>`_)
* Removing Old Connext Tests (`#2313 <https://github.com/ros2/rclcpp/issues/2313>`_)
* Documentation for list_parameters (`#2315 <https://github.com/ros2/rclcpp/issues/2315>`_)
* Decouple rosout publisher init from node init. (`#2174 <https://github.com/ros2/rclcpp/issues/2174>`_)
* fix the depth to relative in list_parameters (`#2300 <https://github.com/ros2/rclcpp/issues/2300>`_)
* Contributors: Chris Lalancette, Lucas Wendland, Minju, Lee, Tomoya Fujita, Tully Foote

23.0.0 (2023-09-08)
-------------------
* Fix the return type of Rate::period. (`#2301 <https://github.com/ros2/rclcpp/issues/2301>`_)
* Update API docs links in package READMEs (`#2302 <https://github.com/ros2/rclcpp/issues/2302>`_)
* Cleanup flaky timers_manager tests. (`#2299 <https://github.com/ros2/rclcpp/issues/2299>`_)
* Contributors: Chris Lalancette, Christophe Bedard

22.2.0 (2023-09-07)
-------------------
* Topic correct typeadapter deduction (`#2294 <https://github.com/ros2/rclcpp/issues/2294>`_)
* Fix C++20 allocator construct deprecation (`#2292 <https://github.com/ros2/rclcpp/issues/2292>`_)
* Make Rate to select the clock to work with (`#2123 <https://github.com/ros2/rclcpp/issues/2123>`_)
* Correct the position of a comment. (`#2290 <https://github.com/ros2/rclcpp/issues/2290>`_)
* Remove unnecessary lambda captures in the tests. (`#2289 <https://github.com/ros2/rclcpp/issues/2289>`_)
* Add rcl_logging_interface as an explicit dependency. (`#2284 <https://github.com/ros2/rclcpp/issues/2284>`_)
* Revamp list_parameters to be more efficient and easier to read. (`#2282 <https://github.com/ros2/rclcpp/issues/2282>`_)
* Contributors: AiVerisimilitude, Alexey Merzlyakov, Chen Lihui, Chris Lalancette, Jiaqi Li

22.1.0 (2023-08-21)
-------------------
* Do not crash Executor when send_response fails due to client failure. (`#2276 <https://github.com/ros2/rclcpp/issues/2276>`_)
* Adding Custom Unknown Type Error (`#2272 <https://github.com/ros2/rclcpp/issues/2272>`_)
* Add a pimpl inside rclcpp::Node for future distro backports (`#2228 <https://github.com/ros2/rclcpp/issues/2228>`_)
* Remove an unused variable from the events executor tests. (`#2270 <https://github.com/ros2/rclcpp/issues/2270>`_)
* Add spin_all shortcut (`#2246 <https://github.com/ros2/rclcpp/issues/2246>`_)
* Adding Missing Group Exceptions (`#2256 <https://github.com/ros2/rclcpp/issues/2256>`_)
* Change associated clocks storage to unordered_set (`#2257 <https://github.com/ros2/rclcpp/issues/2257>`_)
* associated clocks should be protected by mutex. (`#2255 <https://github.com/ros2/rclcpp/issues/2255>`_)
* Instrument loaned message publication code path (`#2240 <https://github.com/ros2/rclcpp/issues/2240>`_)
* Contributors: Chris Lalancette, Christophe Bedard, Emerson Knapp, Luca Della Vedova, Lucas Wendland, Tomoya Fujita, Tony Najjar

22.0.0 (2023-07-11)
-------------------
* Implement get_node_type_descriptions_interface for lifecyclenode and add smoke test for it (`#2237 <https://github.com/ros2/rclcpp/issues/2237>`_)
* Add new node interface TypeDescriptionsInterface to provide GetTypeDescription service (`#2224 <https://github.com/ros2/rclcpp/issues/2224>`_)
* Move always_false_v to detail namespace (`#2232 <https://github.com/ros2/rclcpp/issues/2232>`_)
* Revamp the test_subscription.cpp tests. (`#2227 <https://github.com/ros2/rclcpp/issues/2227>`_)
* warning: comparison of integer expressions of different signedness (`#2219 <https://github.com/ros2/rclcpp/issues/2219>`_)
* Modifies timers API to select autostart state (`#2005 <https://github.com/ros2/rclcpp/issues/2005>`_)
* Enable callback group tests for connextdds (`#2182 <https://github.com/ros2/rclcpp/issues/2182>`_)
* Contributors: Chris Lalancette, Christopher Wecht, Eloy Briceno, Emerson Knapp, Nathan Wiebe Neufeldt, Tomoya Fujita

21.3.0 (2023-06-12)
-------------------
* Fix up misspellings of "receive". (`#2208 <https://github.com/ros2/rclcpp/issues/2208>`_)
* Remove flaky stressAddRemoveNode test (`#2206 <https://github.com/ros2/rclcpp/issues/2206>`_)
* Use TRACETOOLS\_ prefix for tracepoint-related macros (`#2162 <https://github.com/ros2/rclcpp/issues/2162>`_)
* Contributors: Chris Lalancette, Christophe Bedard, Michael Carroll

21.2.0 (2023-06-07)
-------------------
* remove nolint since ament_cpplint updated for the c++17 header (`#2198 <https://github.com/ros2/rclcpp/issues/2198>`_)
Expand Down
4 changes: 4 additions & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ find_package(builtin_interfaces REQUIRED)
find_package(libstatistics_collector REQUIRED)
find_package(rcl REQUIRED)
find_package(rcl_interfaces REQUIRED)
find_package(rcl_logging_interface REQUIRED)
find_package(rcl_yaml_param_parser REQUIRED)
find_package(rcpputils REQUIRED)
find_package(rcutils REQUIRED)
Expand Down Expand Up @@ -92,6 +93,7 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/node_interfaces/node_time_source.cpp
src/rclcpp/node_interfaces/node_timers.cpp
src/rclcpp/node_interfaces/node_topics.cpp
src/rclcpp/node_interfaces/node_type_descriptions.cpp
src/rclcpp/node_interfaces/node_waitables.cpp
src/rclcpp/node_options.cpp
src/rclcpp/parameter.cpp
Expand All @@ -105,6 +107,7 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/qos.cpp
src/rclcpp/event_handler.cpp
src/rclcpp/qos_overriding_options.cpp
src/rclcpp/rate.cpp
src/rclcpp/serialization.cpp
src/rclcpp/serialized_message.cpp
src/rclcpp/service.cpp
Expand Down Expand Up @@ -206,6 +209,7 @@ ament_target_dependencies(${PROJECT_NAME}
"libstatistics_collector"
"rcl"
"rcl_interfaces"
"rcl_logging_interface"
"rcl_yaml_param_parser"
"rcpputils"
"rcutils"
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

The ROS client library in C++.

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

## Quality Declaration

Expand Down
14 changes: 7 additions & 7 deletions rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,15 +34,15 @@
#include "rclcpp/type_adapter.hpp"


template<class>
inline constexpr bool always_false_v = false;

namespace rclcpp
{

namespace detail
{

template<class>
inline constexpr bool always_false_v = false;

template<typename MessageT, typename AllocatorT>
struct MessageDeleterHelper
{
Expand Down Expand Up @@ -580,7 +580,7 @@ class AnySubscriptionCallback
}
// condition to catch unhandled callback types
else { // NOLINT[readability/braces]
static_assert(always_false_v<T>, "unhandled callback type");
static_assert(detail::always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
Expand Down Expand Up @@ -660,7 +660,7 @@ class AnySubscriptionCallback
}
// condition to catch unhandled callback types
else { // NOLINT[readability/braces]
static_assert(always_false_v<T>, "unhandled callback type");
static_assert(detail::always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
Expand Down Expand Up @@ -790,7 +790,7 @@ class AnySubscriptionCallback
}
// condition to catch unhandled callback types
else { // NOLINT[readability/braces]
static_assert(always_false_v<T>, "unhandled callback type");
static_assert(detail::always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
Expand Down Expand Up @@ -924,7 +924,7 @@ class AnySubscriptionCallback
}
// condition to catch unhandled callback types
else { // NOLINT[readability/braces]
static_assert(always_false_v<T>, "unhandled callback type");
static_assert(detail::always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
Expand Down
82 changes: 82 additions & 0 deletions rclcpp/include/rclcpp/copy_all_parameter_values.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
// Copyright 2023 Open Navigation LLC
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RCLCPP__COPY_ALL_PARAMETER_VALUES_HPP_
#define RCLCPP__COPY_ALL_PARAMETER_VALUES_HPP_

#include <string>
#include <vector>

#include "rcl_interfaces/srv/list_parameters.hpp"
#include "rcl_interfaces/msg/parameter_descriptor.hpp"
#include "rcl_interfaces/msg/set_parameters_result.hpp"

#include "rclcpp/parameter.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/logging.hpp"

namespace rclcpp
{

/**
* Copy all parameters from one source node to another destination node.
* May throw exceptions if parameters from source are uninitialized or undeclared.
* \param source Node to copy parameters from
* \param destination Node to copy parameters to
* \param override_existing_params Default false. Whether to override existing destination params
* if both the source and destination contain the same parameter.
*/
template<typename NodeT1, typename NodeT2>
void
copy_all_parameter_values(
const NodeT1 & source, const NodeT2 & destination, const bool override_existing_params = false)
{
using Parameters = std::vector<rclcpp::Parameter>;
using Descriptions = std::vector<rcl_interfaces::msg::ParameterDescriptor>;
auto source_params = source->get_node_parameters_interface();
auto dest_params = destination->get_node_parameters_interface();
rclcpp::Logger logger = destination->get_node_logging_interface()->get_logger();

std::vector<std::string> param_names = source_params->list_parameters({}, 0).names;
Parameters params = source_params->get_parameters(param_names);
Descriptions descriptions = source_params->describe_parameters(param_names);

for (unsigned int idx = 0; idx != params.size(); idx++) {
if (!dest_params->has_parameter(params[idx].get_name())) {
dest_params->declare_parameter(
params[idx].get_name(), params[idx].get_parameter_value(), descriptions[idx]);
} else if (override_existing_params) {
try {
rcl_interfaces::msg::SetParametersResult result =
dest_params->set_parameters_atomically({params[idx]});
if (!result.successful) {
// Parameter update rejected or read-only
RCLCPP_WARN(
logger,
"Unable to set parameter (%s): %s!",
params[idx].get_name().c_str(), result.reason.c_str());
}
} catch (const rclcpp::exceptions::InvalidParameterTypeException & e) {
RCLCPP_WARN(
logger,
"Unable to set parameter (%s): incompatable parameter type (%s)!",
params[idx].get_name().c_str(), e.what());
}
}
}
}

} // namespace rclcpp

#endif // RCLCPP__COPY_ALL_PARAMETER_VALUES_HPP_
17 changes: 8 additions & 9 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,8 @@ template<
typename SubscriptionT,
typename MessageMemoryStrategyT,
typename NodeParametersT,
typename NodeTopicsT,
typename ROSMessageType = typename SubscriptionT::ROSMessageType>
typename NodeTopicsT
>
typename std::shared_ptr<SubscriptionT>
create_subscription(
NodeParametersT & node_parameters,
Expand All @@ -70,7 +70,7 @@ create_subscription(
using rclcpp::node_interfaces::get_node_topics_interface;
auto node_topics_interface = get_node_topics_interface(node_topics);

std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<ROSMessageType>>
std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics>
subscription_topic_stats = nullptr;

if (rclcpp::detail::resolve_enable_topic_statistics(
Expand All @@ -80,8 +80,7 @@ create_subscription(
if (options.topic_stats_options.publish_period <= std::chrono::milliseconds(0)) {
throw std::invalid_argument(
"topic_stats_options.publish_period must be greater than 0, specified value of " +
std::to_string(options.topic_stats_options.publish_period.count()) +
" ms");
std::to_string(options.topic_stats_options.publish_period.count()) + " ms");
}

std::shared_ptr<Publisher<statistics_msgs::msg::MetricsMessage>>
Expand All @@ -91,12 +90,12 @@ create_subscription(
options.topic_stats_options.publish_topic,
qos);

subscription_topic_stats = std::make_shared<
rclcpp::topic_statistics::SubscriptionTopicStatistics<ROSMessageType>
>(node_topics_interface->get_node_base_interface()->get_name(), publisher);
subscription_topic_stats =
std::make_shared<rclcpp::topic_statistics::SubscriptionTopicStatistics>(
node_topics_interface->get_node_base_interface()->get_name(), publisher);

std::weak_ptr<
rclcpp::topic_statistics::SubscriptionTopicStatistics<ROSMessageType>
rclcpp::topic_statistics::SubscriptionTopicStatistics
> weak_subscription_topic_stats(subscription_topic_stats);
auto sub_call_back = [weak_subscription_topic_stats]() {
auto subscription_topic_stats = weak_subscription_topic_stats.lock();
Expand Down
23 changes: 15 additions & 8 deletions rclcpp/include/rclcpp/create_timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,15 +90,17 @@ create_timer(
rclcpp::Clock::SharedPtr clock,
rclcpp::Duration period,
CallbackT && callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr)
rclcpp::CallbackGroup::SharedPtr group = nullptr,
bool autostart = true)
{
return create_timer(
clock,
period.to_chrono<std::chrono::nanoseconds>(),
std::forward<CallbackT>(callback),
group,
node_base.get(),
node_timers.get());
node_timers.get(),
autostart);
}

/// Create a timer with a given clock
Expand All @@ -109,15 +111,17 @@ create_timer(
rclcpp::Clock::SharedPtr clock,
rclcpp::Duration period,
CallbackT && callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr)
rclcpp::CallbackGroup::SharedPtr group = nullptr,
bool autostart = true)
{
return create_timer(
clock,
period.to_chrono<std::chrono::nanoseconds>(),
std::forward<CallbackT>(callback),
group,
rclcpp::node_interfaces::get_node_base_interface(node).get(),
rclcpp::node_interfaces::get_node_timers_interface(node).get());
rclcpp::node_interfaces::get_node_timers_interface(node).get(),
autostart);
}

/// Convenience method to create a general timer with node resources.
Expand All @@ -132,6 +136,7 @@ create_timer(
* \param group callback group
* \param node_base node base interface
* \param node_timers node timer interface
* \param autostart defines if the timer should start it's countdown on initialization or not.
* \return shared pointer to a generic timer
* \throws std::invalid_argument if either clock, node_base or node_timers
* are nullptr, or period is negative or too large
Expand All @@ -144,7 +149,8 @@ create_timer(
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group,
node_interfaces::NodeBaseInterface * node_base,
node_interfaces::NodeTimersInterface * node_timers)
node_interfaces::NodeTimersInterface * node_timers,
bool autostart = true)
{
if (clock == nullptr) {
throw std::invalid_argument{"clock cannot be null"};
Expand All @@ -160,7 +166,7 @@ create_timer(

// Add a new generic timer.
auto timer = rclcpp::GenericTimer<CallbackT>::make_shared(
std::move(clock), period_ns, std::move(callback), node_base->get_context());
std::move(clock), period_ns, std::move(callback), node_base->get_context(), autostart);
node_timers->add_timer(timer, group);
return timer;
}
Expand All @@ -187,7 +193,8 @@ create_wall_timer(
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group,
node_interfaces::NodeBaseInterface * node_base,
node_interfaces::NodeTimersInterface * node_timers)
node_interfaces::NodeTimersInterface * node_timers,
bool autostart = true)
{
if (node_base == nullptr) {
throw std::invalid_argument{"input node_base cannot be null"};
Expand All @@ -201,7 +208,7 @@ create_wall_timer(

// Add a new wall timer.
auto timer = rclcpp::WallTimer<CallbackT>::make_shared(
period_ns, std::move(callback), node_base->get_context());
period_ns, std::move(callback), node_base->get_context(), autostart);
node_timers->add_timer(timer, group);
return timer;
}
Expand Down
Loading

0 comments on commit 8843d54

Please sign in to comment.