From d5d17d6a0a70e6862bda790c631c457a926ccdc8 Mon Sep 17 00:00:00 2001 From: Abishalini Date: Tue, 1 Nov 2022 09:07:15 -0600 Subject: [PATCH] Add deprecated tag --- .../include/moveit/kinematics_base/kinematics_base.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index 704f197eeb..903be4d2af 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -604,8 +604,8 @@ class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase * as the predominant configuration but also allows groupwise specifications. */ template - inline bool lookupParam(const rclcpp::Node::SharedPtr& node, const std::string& param, T& val, - const T& default_val) const + [[deprecated("Use generate_parameter_library instead")]] inline bool + lookupParam(const rclcpp::Node::SharedPtr& node, const std::string& param, T& val, const T& default_val) const { if (node->has_parameter({ group_name_ + "." + param })) {