diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp index f4bfb4f592..9b7507f750 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -67,18 +67,6 @@ enum class InterpolationMethod */ const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_DEGREE_SPLINE; -/** - * @brief Maps string representations to their corresponding InterpolationMethod enum values. - * - * @deprecated This map is deprecated. Use the direct lookup methods instead. - * (Original use: Converting strings into the InterpolationMethod). - */ -[[deprecated( - "InterpolationMethodMap will be removed in future releases. " - "Instead, use the direct lookup methods.")]] -const std::unordered_map InterpolationMethodMap( - {{"none", InterpolationMethod::NONE}, {"splines", InterpolationMethod::VARIABLE_DEGREE_SPLINE}}); - /** * \brief Returns corresponding string value for the `InterpolationMethod`. * This function uses simple switch-case lookup to directly assign string value to