Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

added conditioning to have rolling tags compilable in older versions #1422

Merged
merged 3 commits into from
Mar 2, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,13 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
CONTROLLER_INTERFACE_PUBLIC
virtual rclcpp::NodeOptions define_custom_node_options() const
{
#if RCLCPP_VERSION_MAJOR >= 21
return rclcpp::NodeOptions().enable_logger_service(true);
#else
return rclcpp::NodeOptions()
.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true);
#endif
}

/// Declare and initialize a parameter with a type.
Expand Down
13 changes: 13 additions & 0 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,10 +36,23 @@ static constexpr const char * kChainableControllerInterfaceClassName =
"controller_interface::ChainableControllerInterface";

// Changed services history QoS to keep all so we don't lose any client service calls
#if RCLCPP_VERSION_MAJOR >= 17
rclcpp::QoS qos_services =
rclcpp::QoS(rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 1))
.reliable()
.durability_volatile();
#else
static const rmw_qos_profile_t qos_services = {
RMW_QOS_POLICY_HISTORY_KEEP_ALL,
1, // message queue depth
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
RMW_QOS_POLICY_DURABILITY_VOLATILE,
RMW_QOS_DEADLINE_DEFAULT,
RMW_QOS_LIFESPAN_DEFAULT,
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
false};
#endif

inline bool is_controller_inactive(const controller_interface::ControllerInterfaceBase & controller)
{
Expand Down
Loading