Skip to content

Commit 63c11a4

Browse files
committed
Add 'best available' QoS enum values and methods
If users set a policy as 'best available', then the middleware will pick a policy that is most compatible with the current set of discovered endpoints while maintaining the highest level of service possible. For details about the expected behavior, see connected changes: - ros2/rmw#320 - ros2/rmw_dds_common#60 Signed-off-by: Jacob Perron <[email protected]>
1 parent 85a7046 commit 63c11a4

File tree

3 files changed

+66
-0
lines changed

3 files changed

+66
-0
lines changed

rclcpp/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_

rclcpp/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

rclcpp/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)