Skip to content

Commit 41a617c

Browse files
committed
New upstream version 16.2.0
1 parent 929aca3 commit 41a617c

File tree

10 files changed

+117
-10
lines changed

10 files changed

+117
-10
lines changed

CHANGELOG.rst

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

5+
16.2.0 (2022-05-03)
6+
-------------------
7+
* Update get_parameter_from_event to follow the function description (`#1922 <https://github.com/ros2/rclcpp/issues/1922>`_)
8+
* Add 'best available' QoS enum values and methods (`#1920 <https://github.com/ros2/rclcpp/issues/1920>`_)
9+
* Contributors: Barry Xu, Jacob Perron
10+
11+
16.1.0 (2022-04-29)
12+
-------------------
13+
* use reinterpret_cast for function pointer conversion. (`#1919 <https://github.com/ros2/rclcpp/issues/1919>`_)
14+
* Contributors: Tomoya Fujita
15+
516
16.0.1 (2022-04-13)
617
-------------------
718
* remove DEFINE_CONTENT_FILTER cmake option (`#1914 <https://github.com/ros2/rclcpp/issues/1914>`_)

include/rclcpp/parameter_event_handler.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -268,6 +268,7 @@ class ParameterEventHandler
268268
* \param[in] parameter_name Name of parameter.
269269
* \param[in] node_name Name of node which hosts the parameter.
270270
* \returns The resultant rclcpp::Parameter from the event.
271+
* \throws std::runtime_error if input node name doesn't match the node name in parameter event.
271272
*/
272273
RCLCPP_PUBLIC
273274
static rclcpp::Parameter

include/rclcpp/qos.hpp

Lines changed: 41 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ enum class ReliabilityPolicy
4444
BestEffort = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT,
4545
Reliable = RMW_QOS_POLICY_RELIABILITY_RELIABLE,
4646
SystemDefault = RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT,
47+
BestAvailable = RMW_QOS_POLICY_RELIABILITY_BEST_AVAILABLE,
4748
Unknown = RMW_QOS_POLICY_RELIABILITY_UNKNOWN,
4849
};
4950

@@ -52,6 +53,7 @@ enum class DurabilityPolicy
5253
Volatile = RMW_QOS_POLICY_DURABILITY_VOLATILE,
5354
TransientLocal = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
5455
SystemDefault = RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT,
56+
BestAvailable = RMW_QOS_POLICY_DURABILITY_BEST_AVAILABLE,
5557
Unknown = RMW_QOS_POLICY_DURABILITY_UNKNOWN,
5658
};
5759

@@ -60,6 +62,7 @@ enum class LivelinessPolicy
6062
Automatic = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC,
6163
ManualByTopic = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC,
6264
SystemDefault = RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
65+
BestAvailable = RMW_QOS_POLICY_LIVELINESS_BEST_AVAILABLE,
6366
Unknown = RMW_QOS_POLICY_LIVELINESS_UNKNOWN,
6467
};
6568

@@ -180,6 +183,10 @@ class RCLCPP_PUBLIC QoS
180183
QoS &
181184
best_effort();
182185

186+
/// Set the reliability setting to best available.
187+
QoS &
188+
reliability_best_available();
189+
183190
/// Set the durability setting.
184191
QoS &
185192
durability(rmw_qos_durability_policy_t durability);
@@ -199,6 +206,10 @@ class RCLCPP_PUBLIC QoS
199206
QoS &
200207
transient_local();
201208

209+
/// Set the durability setting to best available.
210+
QoS &
211+
durability_best_available();
212+
202213
/// Set the deadline setting.
203214
QoS &
204215
deadline(rmw_time_t deadline);
@@ -488,6 +499,36 @@ class RCLCPP_PUBLIC SystemDefaultsQoS : public QoS
488499
));
489500
};
490501

502+
/**
503+
* Best available QoS class
504+
*
505+
* Match majority of endpoints currently available while maintaining the highest level of service.
506+
* Policies are chosen at the time of creating a subscription or publisher.
507+
* The middleware is not expected to update policies after creating a subscription or publisher,
508+
* even if one or more policies are incompatible with newly discovered endpoints.
509+
* Therefore, this profile should be used with care since non-deterministic behavior can occur due
510+
* to races with discovery.
511+
*
512+
* - History: Keep last,
513+
* - Depth: 10,
514+
* - Reliability: Best available,
515+
* - Durability: Best available,
516+
* - Deadline: Best available,
517+
* - Lifespan: Default,
518+
* - Liveliness: Best available,
519+
* - Liveliness lease duration: Best available,
520+
* - avoid ros namespace conventions: false
521+
*/
522+
class RCLCPP_PUBLIC BestAvailableQoS : public QoS
523+
{
524+
public:
525+
explicit
526+
BestAvailableQoS(
527+
const QoSInitialization & qos_initialization = (
528+
QoSInitialization::from_rmw(rmw_qos_profile_best_available)
529+
));
530+
};
531+
491532
} // namespace rclcpp
492533

493534
#endif // RCLCPP__QOS_HPP_

include/rclcpp/timer.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -189,10 +189,10 @@ class GenericTimer : public TimerBase
189189
TRACEPOINT(
190190
rclcpp_timer_callback_added,
191191
static_cast<const void *>(get_timer_handle().get()),
192-
static_cast<const void *>(&callback_));
192+
reinterpret_cast<const void *>(&callback_));
193193
TRACEPOINT(
194194
rclcpp_callback_register,
195-
static_cast<const void *>(&callback_),
195+
reinterpret_cast<const void *>(&callback_),
196196
tracetools::get_symbol(callback_));
197197
}
198198

@@ -226,9 +226,9 @@ class GenericTimer : public TimerBase
226226
void
227227
execute_callback() override
228228
{
229-
TRACEPOINT(callback_start, static_cast<const void *>(&callback_), false);
229+
TRACEPOINT(callback_start, reinterpret_cast<const void *>(&callback_), false);
230230
execute_callback_delegate<>();
231-
TRACEPOINT(callback_end, static_cast<const void *>(&callback_));
231+
TRACEPOINT(callback_end, reinterpret_cast<const void *>(&callback_));
232232
}
233233

234234
// void specialization

package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="2">
44
<name>rclcpp</name>
5-
<version>16.0.1</version>
5+
<version>16.2.0</version>
66
<description>The ROS client library in C++.</description>
77
<maintainer email="[email protected]">Ivan Paunovic</maintainer>
88
<maintainer email="[email protected]">Jacob Perron</maintainer>

src/rclcpp/parameter_event_handler.cpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -133,9 +133,13 @@ ParameterEventHandler::get_parameter_from_event(
133133
{
134134
rclcpp::Parameter p;
135135
if (!get_parameter_from_event(event, p, parameter_name, node_name)) {
136-
throw std::runtime_error(
137-
"Parameter '" + parameter_name + "' of node '" + node_name +
138-
"' is not part of parameter event");
136+
if (event.node == node_name) {
137+
return rclcpp::Parameter(parameter_name, rclcpp::PARAMETER_NOT_SET);
138+
} else {
139+
throw std::runtime_error(
140+
"The node name '" + node_name + "' of parameter '" + parameter_name +
141+
+"' doesn't match the node name '" + event.node + "' in parameter event");
142+
}
139143
}
140144
return p;
141145
}

src/rclcpp/qos.cpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -150,6 +150,12 @@ QoS::best_effort()
150150
return this->reliability(RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT);
151151
}
152152

153+
QoS &
154+
QoS::reliability_best_available()
155+
{
156+
return this->reliability(RMW_QOS_POLICY_RELIABILITY_BEST_AVAILABLE);
157+
}
158+
153159
QoS &
154160
QoS::durability(rmw_qos_durability_policy_t durability)
155161
{
@@ -176,6 +182,12 @@ QoS::transient_local()
176182
return this->durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
177183
}
178184

185+
QoS &
186+
QoS::durability_best_available()
187+
{
188+
return this->durability(RMW_QOS_POLICY_DURABILITY_BEST_AVAILABLE);
189+
}
190+
179191
QoS &
180192
QoS::deadline(rmw_time_t deadline)
181193
{
@@ -380,4 +392,8 @@ SystemDefaultsQoS::SystemDefaultsQoS(const QoSInitialization & qos_initializatio
380392
: QoS(qos_initialization, rmw_qos_profile_system_default)
381393
{}
382394

395+
BestAvailableQoS::BestAvailableQoS(const QoSInitialization & qos_initialization)
396+
: QoS(qos_initialization, rmw_qos_profile_best_available)
397+
{}
398+
383399
} // namespace rclcpp

test/rclcpp/test_create_timer.cpp

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -116,3 +116,20 @@ TEST(TestCreateTimer, call_wall_timer_with_bad_arguments)
116116
std::invalid_argument);
117117
rclcpp::shutdown();
118118
}
119+
120+
static void test_timer_callback(void) {}
121+
122+
TEST(TestCreateTimer, timer_function_pointer)
123+
{
124+
rclcpp::init(0, nullptr);
125+
auto node = std::make_shared<rclcpp::Node>("timer_function_pointer_node");
126+
127+
// make sure build succeeds with function pointer instead of lambda
128+
auto some_timer = rclcpp::create_timer(
129+
node,
130+
node->get_clock(),
131+
rclcpp::Duration(0ms),
132+
test_timer_callback);
133+
134+
rclcpp::shutdown();
135+
}

test/rclcpp/test_parameter_event_handler.cpp

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -202,9 +202,17 @@ TEST_F(TestNode, GetParameterFromEvent)
202202
EXPECT_THROW(
203203
ParameterEventHandler::get_parameter_from_event(*multiple, "my_int", wrong_name),
204204
std::runtime_error);
205-
// Throws if parameter not part of event
205+
206+
// Parameter not part of event
207+
// with correct node
208+
rclcpp::Parameter expect_notset_ret("my_notset", rclcpp::PARAMETER_NOT_SET);
209+
rclcpp::Parameter ret;
210+
EXPECT_NO_THROW(
211+
ret = ParameterEventHandler::get_parameter_from_event(*multiple, "my_notset", node_name););
212+
EXPECT_EQ(ret, expect_notset_ret);
213+
// with incorrect node
206214
EXPECT_THROW(
207-
ParameterEventHandler::get_parameter_from_event(*diff_ns_bool, "my_int", node_name),
215+
ParameterEventHandler::get_parameter_from_event(*multiple, "my_notset", wrong_name),
208216
std::runtime_error);
209217
}
210218

test/rclcpp/test_qos.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -93,6 +93,9 @@ TEST(TestQoS, setters_and_getters) {
9393
qos.reliable();
9494
EXPECT_EQ(rclcpp::ReliabilityPolicy::Reliable, qos.reliability());
9595

96+
qos.reliability_best_available();
97+
EXPECT_EQ(rclcpp::ReliabilityPolicy::BestAvailable, qos.reliability());
98+
9699
qos.reliability(rclcpp::ReliabilityPolicy::BestEffort);
97100
EXPECT_EQ(rclcpp::ReliabilityPolicy::BestEffort, qos.reliability());
98101

@@ -102,6 +105,9 @@ TEST(TestQoS, setters_and_getters) {
102105
qos.transient_local();
103106
EXPECT_EQ(rclcpp::DurabilityPolicy::TransientLocal, qos.durability());
104107

108+
qos.durability_best_available();
109+
EXPECT_EQ(rclcpp::DurabilityPolicy::BestAvailable, qos.durability());
110+
105111
qos.durability(rclcpp::DurabilityPolicy::Volatile);
106112
EXPECT_EQ(rclcpp::DurabilityPolicy::Volatile, qos.durability());
107113

@@ -183,6 +189,9 @@ TEST(TestQoS, DerivedTypes) {
183189
const rclcpp::KeepLast expected_initialization(RMW_QOS_POLICY_DEPTH_SYSTEM_DEFAULT);
184190
const rclcpp::QoS expected_default(expected_initialization);
185191
EXPECT_EQ(expected_default.get_rmw_qos_profile(), system_default_qos.get_rmw_qos_profile());
192+
193+
rclcpp::BestAvailableQoS best_available_qos;
194+
EXPECT_EQ(rmw_qos_profile_best_available, best_available_qos.get_rmw_qos_profile());
186195
}
187196

188197
TEST(TestQoS, policy_name_from_kind) {

0 commit comments

Comments
 (0)