Skip to content

Commit 81b67a1

Browse files
authored
added conditioning to have rolling tags compilable in older versions (ros-controls#1422)
1 parent 0711cd6 commit 81b67a1

File tree

2 files changed

+21
-0
lines changed

2 files changed

+21
-0
lines changed

controller_interface/include/controller_interface/controller_interface_base.hpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -172,7 +172,14 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
172172
CONTROLLER_INTERFACE_PUBLIC
173173
virtual rclcpp::NodeOptions define_custom_node_options() const
174174
{
175+
// \note The versions conditioning is added here to support the source-compatibility with Humble
176+
#if RCLCPP_VERSION_MAJOR >= 21
175177
return rclcpp::NodeOptions().enable_logger_service(true);
178+
#else
179+
return rclcpp::NodeOptions()
180+
.allow_undeclared_parameters(true)
181+
.automatically_declare_parameters_from_overrides(true);
182+
#endif
176183
}
177184

178185
/// Declare and initialize a parameter with a type.

controller_manager/src/controller_manager.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,10 +36,24 @@ static constexpr const char * kChainableControllerInterfaceClassName =
3636
"controller_interface::ChainableControllerInterface";
3737

3838
// Changed services history QoS to keep all so we don't lose any client service calls
39+
// \note The versions conditioning is added here to support the source-compatibility with Humble
40+
#if RCLCPP_VERSION_MAJOR >= 17
3941
rclcpp::QoS qos_services =
4042
rclcpp::QoS(rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 1))
4143
.reliable()
4244
.durability_volatile();
45+
#else
46+
static const rmw_qos_profile_t qos_services = {
47+
RMW_QOS_POLICY_HISTORY_KEEP_ALL,
48+
1, // message queue depth
49+
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
50+
RMW_QOS_POLICY_DURABILITY_VOLATILE,
51+
RMW_QOS_DEADLINE_DEFAULT,
52+
RMW_QOS_LIFESPAN_DEFAULT,
53+
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
54+
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
55+
false};
56+
#endif
4357

4458
inline bool is_controller_inactive(const controller_interface::ControllerInterfaceBase & controller)
4559
{

0 commit comments

Comments
 (0)