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

Fix usage of deprecated AsyncParametersClient constructor #319

Merged
merged 2 commits into from
Jul 30, 2024
Merged
Changes from all commits
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
20 changes: 14 additions & 6 deletions ros2_foxglove_bridge/src/parameter_interface.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
#include "foxglove_bridge/parameter_interface.hpp"

#include <nlohmann/json.hpp>
#include <rclcpp/qos.hpp>
#include <rclcpp/version.h>

#include <foxglove_bridge/regex_utils.hpp>
#include <foxglove_bridge/utils.hpp>
Expand All @@ -9,6 +11,12 @@ namespace {

constexpr char PARAM_SEP = '.';

#if RCLCPP_VERSION_MAJOR > 16
const rclcpp::ParametersQoS parameterQoS;
#else
const rmw_qos_profile_t& parameterQoS = rmw_qos_profile_parameters;
#endif

static std::pair<std::string, std::string> getNodeAndParamName(
const std::string& nodeNameAndParamName) {
return {nodeNameAndParamName.substr(0UL, nodeNameAndParamName.find(PARAM_SEP)),
Expand Down Expand Up @@ -195,8 +203,8 @@ ParameterList ParameterInterface::getParams(const std::vector<std::string>& para
auto paramClientIt = _paramClientsByNode.find(nodeName);
if (paramClientIt == _paramClientsByNode.end()) {
const auto insertedPair = _paramClientsByNode.emplace(
nodeName, rclcpp::AsyncParametersClient::make_shared(
_node, nodeName, rmw_qos_profile_parameters, _callbackGroup));
nodeName,
rclcpp::AsyncParametersClient::make_shared(_node, nodeName, parameterQoS, _callbackGroup));
paramClientIt = insertedPair.first;
}

Expand Down Expand Up @@ -238,8 +246,8 @@ void ParameterInterface::setParams(const ParameterList& parameters,
auto paramClientIt = _paramClientsByNode.find(nodeName);
if (paramClientIt == _paramClientsByNode.end()) {
const auto insertedPair = _paramClientsByNode.emplace(
nodeName, rclcpp::AsyncParametersClient::make_shared(
_node, nodeName, rmw_qos_profile_parameters, _callbackGroup));
nodeName,
rclcpp::AsyncParametersClient::make_shared(_node, nodeName, parameterQoS, _callbackGroup));
paramClientIt = insertedPair.first;
}

Expand Down Expand Up @@ -281,8 +289,8 @@ void ParameterInterface::subscribeParams(const std::vector<std::string>& paramNa
auto paramClientIt = _paramClientsByNode.find(nodeName);
if (paramClientIt == _paramClientsByNode.end()) {
const auto insertedPair = _paramClientsByNode.emplace(
nodeName, rclcpp::AsyncParametersClient::make_shared(
_node, nodeName, rmw_qos_profile_parameters, _callbackGroup));
nodeName,
rclcpp::AsyncParametersClient::make_shared(_node, nodeName, parameterQoS, _callbackGroup));
paramClientIt = insertedPair.first;
}

Expand Down
Loading