From 1199a54493ee11ff2f713975737fde4af50a3697 Mon Sep 17 00:00:00 2001 From: Mystic Devloper Date: Fri, 21 Nov 2025 18:09:44 +0530 Subject: [PATCH 01/29] Refactor: interpolation_method.hpp --- .../interpolation_methods.hpp | 80 ++++++++++++++++--- 1 file changed, 69 insertions(+), 11 deletions(-) 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 f357a312c5..c256c3b86b 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -22,43 +22,101 @@ namespace joint_trajectory_controller { + +/// \brief Setup interpolation_methods' rclcpp::Logger instance. static const rclcpp::Logger LOGGER = rclcpp::get_logger("joint_trajectory_controller.interpolation_methods"); namespace interpolation_methods { + +/** + * \brief Defines the available interpolation methods used for fitting data curves. + * This enumeration specifies how intermediate values between data points + * should be calculated. + */ enum class InterpolationMethod { + /** + * \brief No interpolation is performed. + * This is typically used when data points are discrete and should not be + * connected by a curve. + */ NONE, + + /** + * \brief Uses a variable-degree spline interpolation. + * The degree of the spline is determined dynamically based on the number of + * available deriviatives. This provides a smooth, continuous curve between data points. + * + * Based on available deriviatives, it uses following degree interpolation, + * 1. Neither velocity nor acceleration is available: `Linear Interpolation`. + * 2. Velocity is available, but acceleration is not available: `Cubic Spline Interpolation`. + * 3. Both velocity and acceleration is available: `Quintic Spline Interpolation`. + */ VARIABLE_DEGREE_SPLINE }; +/** + * \brief The default interpolation method is set to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`. + * As, it provides most realistic, jerk-free and smooth motion. + */ const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_DEGREE_SPLINE; -const std::unordered_map InterpolationMethodMap( - {{InterpolationMethod::NONE, "none"}, {InterpolationMethod::VARIABLE_DEGREE_SPLINE, "splines"}}); +/** + * \brief Maps `InterpolationMethod` enum values to their string identifiers. + * This constant map is used to look up the InterpolationMethod for a given + * string (e.g., "splines" for `VARIABLE_DEGREE_SPLINE`). + */ +const std::unordered_map InterpolationMethodMap({ + {"none", InterpolationMethod::NONE}, + {"splines", InterpolationMethod::VARIABLE_DEGREE_SPLINE} +}); +/** + * \brief Reverse map of InterpolationMethodMap. + * This constant map is used to look up the string name for a given + * InterpolationMethod (e.g., `VARIABLE_DEGREE_SPLINE` for "splines"). + */ +const std::unordered_map ReverseInterpolationMethodMap({ + {InterpolationMethod::NONE, "none"}, + {InterpolationMethod::VARIABLE_DEGREE_SPLINE, "splines"} +}); + +/** + * \brief Creates a `InterpolationMethod` enum class value from a string. + * This function looks up `InterpolationMethodMap` for corresponding `InterpolationMethod` based + * on interpolation_method string. + * + * \param[in] `interpolation_method` The given interpolation method `string`. + * + * \returns The corresponding InterpolationMethod. + * + * \note If interpolation_method do not have any corresponding InterpolationMethod (i.e., Unknown), + * It defaults to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`. + */ [[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method) { - if (interpolation_method.compare(InterpolationMethodMap.at(InterpolationMethod::NONE)) == 0) - { - return InterpolationMethod::NONE; - } - else if ( - interpolation_method.compare( - InterpolationMethodMap.at(InterpolationMethod::VARIABLE_DEGREE_SPLINE)) == 0) + // Iterator to InterpolationMethodMap + const auto iterator = InterpolationMethodMap.find(interpolation_method); + + // If interpolation_method exists + if (iterator != InterpolationMethodMap.end()) { - return InterpolationMethod::VARIABLE_DEGREE_SPLINE; + // Return corresponding `InterpolationMethod` + return iterator->second; } // Default else { RCLCPP_INFO( LOGGER, - "No interpolation method parameter was given. Using the default, VARIABLE_DEGREE_SPLINE."); + "Unknown interpolation method parameter '%s' was given. Using the default: VARIABLE_DEGREE_SPLINE.", + interpolation_method.c_str()); return InterpolationMethod::VARIABLE_DEGREE_SPLINE; } } + } // namespace interpolation_methods } // namespace joint_trajectory_controller From 011ca307a8f36aa545d3da1f643cd7c5e4fefda0 Mon Sep 17 00:00:00 2001 From: Mystic Devloper Date: Fri, 21 Nov 2025 18:10:48 +0530 Subject: [PATCH 02/29] Refactor: Changed InterpolationMap to ReverseInterpolationMap to reflect changes in interpolation_method.hpp --- joint_trajectory_controller/src/joint_trajectory_controller.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 83d8c05489..c97ce5ccca 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -942,7 +942,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( interpolation_method_ = interpolation_methods::from_string(interpolation_string); RCLCPP_INFO( logger, "Using '%s' interpolation method.", - interpolation_methods::InterpolationMethodMap.at(interpolation_method_).c_str()); + interpolation_methods::ReverseInterpolationMethodMap.at(interpolation_method_).c_str()); // prepare hold_position_msg init_hold_position_msg(); From dfe48b9f3015f158acaf55a0d7fd35c38b2f803c Mon Sep 17 00:00:00 2001 From: Mystic Devloper Date: Mon, 24 Nov 2025 09:34:38 +0530 Subject: [PATCH 03/29] Refactor: Fixed pre-commit stylistic issues. --- .../interpolation_methods.hpp | 17 +++++++---------- 1 file changed, 7 insertions(+), 10 deletions(-) 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 c256c3b86b..73546802d5 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -68,20 +68,16 @@ const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_ * This constant map is used to look up the InterpolationMethod for a given * string (e.g., "splines" for `VARIABLE_DEGREE_SPLINE`). */ -const std::unordered_map InterpolationMethodMap({ - {"none", InterpolationMethod::NONE}, - {"splines", InterpolationMethod::VARIABLE_DEGREE_SPLINE} -}); +const std::unordered_map InterpolationMethodMap( + {{"none", InterpolationMethod::NONE}, {"splines", InterpolationMethod::VARIABLE_DEGREE_SPLINE}}); /** * \brief Reverse map of InterpolationMethodMap. * This constant map is used to look up the string name for a given * InterpolationMethod (e.g., `VARIABLE_DEGREE_SPLINE` for "splines"). */ -const std::unordered_map ReverseInterpolationMethodMap({ - {InterpolationMethod::NONE, "none"}, - {InterpolationMethod::VARIABLE_DEGREE_SPLINE, "splines"} -}); +const std::unordered_map ReverseInterpolationMethodMap( + {{InterpolationMethod::NONE, "none"}, {InterpolationMethod::VARIABLE_DEGREE_SPLINE, "splines"}}); /** * \brief Creates a `InterpolationMethod` enum class value from a string. @@ -89,7 +85,7 @@ const std::unordered_map ReverseInterpolationM * on interpolation_method string. * * \param[in] `interpolation_method` The given interpolation method `string`. - * + * * \returns The corresponding InterpolationMethod. * * \note If interpolation_method do not have any corresponding InterpolationMethod (i.e., Unknown), @@ -111,7 +107,8 @@ const std::unordered_map ReverseInterpolationM { RCLCPP_INFO( LOGGER, - "Unknown interpolation method parameter '%s' was given. Using the default: VARIABLE_DEGREE_SPLINE.", + "Unknown interpolation method parameter '%s' was given. Using the default: " + "VARIABLE_DEGREE_SPLINE.", interpolation_method.c_str()); return InterpolationMethod::VARIABLE_DEGREE_SPLINE; } From 84975fd96c6bf4fc21a7f7a2e582bb0d187d8818 Mon Sep 17 00:00:00 2001 From: TheDevMystic Date: Mon, 24 Nov 2025 12:42:43 +0530 Subject: [PATCH 04/29] Refactor: Changed ReverseInterpolationMethodMap lookup to interpolation_string. --- joint_trajectory_controller/src/joint_trajectory_controller.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index c97ce5ccca..1534663d35 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -942,7 +942,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( interpolation_method_ = interpolation_methods::from_string(interpolation_string); RCLCPP_INFO( logger, "Using '%s' interpolation method.", - interpolation_methods::ReverseInterpolationMethodMap.at(interpolation_method_).c_str()); + interpolation_string.c_str()); // prepare hold_position_msg init_hold_position_msg(); From e4922c8404f624f8f36fc701976c5fe69f01a4a8 Mon Sep 17 00:00:00 2001 From: TheDevMystic Date: Mon, 24 Nov 2025 12:50:41 +0530 Subject: [PATCH 05/29] Remove: Removed redundant ReverseInterpolationMethodMap. --- .../joint_trajectory_controller/interpolation_methods.hpp | 8 -------- 1 file changed, 8 deletions(-) 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 73546802d5..b08d9dd843 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -71,14 +71,6 @@ const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_ const std::unordered_map InterpolationMethodMap( {{"none", InterpolationMethod::NONE}, {"splines", InterpolationMethod::VARIABLE_DEGREE_SPLINE}}); -/** - * \brief Reverse map of InterpolationMethodMap. - * This constant map is used to look up the string name for a given - * InterpolationMethod (e.g., `VARIABLE_DEGREE_SPLINE` for "splines"). - */ -const std::unordered_map ReverseInterpolationMethodMap( - {{InterpolationMethod::NONE, "none"}, {InterpolationMethod::VARIABLE_DEGREE_SPLINE, "splines"}}); - /** * \brief Creates a `InterpolationMethod` enum class value from a string. * This function looks up `InterpolationMethodMap` for corresponding `InterpolationMethod` based From 1ec2608c9f7becaf0c71f8ac54c52da060f6ddf3 Mon Sep 17 00:00:00 2001 From: TheDevMystic Date: Mon, 24 Nov 2025 12:57:20 +0530 Subject: [PATCH 06/29] Refactor: Fixed Stylistic Inconsistency. --- .../src/joint_trajectory_controller.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 1534663d35..765f80fc73 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -940,9 +940,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( const std::string interpolation_string = get_node()->get_parameter("interpolation_method").as_string(); interpolation_method_ = interpolation_methods::from_string(interpolation_string); - RCLCPP_INFO( - logger, "Using '%s' interpolation method.", - interpolation_string.c_str()); + RCLCPP_INFO(logger, "Using '%s' interpolation method.", interpolation_string.c_str()); // prepare hold_position_msg init_hold_position_msg(); From 2aec5a0c799e9026cf93840ecb62bfa65995c743 Mon Sep 17 00:00:00 2001 From: Surya! Date: Mon, 24 Nov 2025 14:40:49 +0530 Subject: [PATCH 07/29] Update joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp Co-authored-by: Felix Exner (fexner) --- .../joint_trajectory_controller/interpolation_methods.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 b08d9dd843..375f042da6 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -76,7 +76,7 @@ const std::unordered_map InterpolationMethodMa * This function looks up `InterpolationMethodMap` for corresponding `InterpolationMethod` based * on interpolation_method string. * - * \param[in] `interpolation_method` The given interpolation method `string`. + * \param[in] interpolation_method The given interpolation method string. * * \returns The corresponding InterpolationMethod. * From f5f4c0d1325de46f5bea9044ca0ba7d07c4c830e Mon Sep 17 00:00:00 2001 From: Surya! Date: Mon, 24 Nov 2025 14:41:20 +0530 Subject: [PATCH 08/29] Update joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp Co-authored-by: Felix Exner (fexner) --- .../joint_trajectory_controller/interpolation_methods.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 375f042da6..ce03b8ba32 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -80,7 +80,7 @@ const std::unordered_map InterpolationMethodMa * * \returns The corresponding InterpolationMethod. * - * \note If interpolation_method do not have any corresponding InterpolationMethod (i.e., Unknown), + * \note If interpolation_method does not have any corresponding InterpolationMethod (i.e., "Unknown"), * It defaults to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`. */ [[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method) From 8f2257b063e614f6dbc661793847022b2e22da82 Mon Sep 17 00:00:00 2001 From: Sai Kishor Kothakota Date: Mon, 24 Nov 2025 10:16:22 +0100 Subject: [PATCH 09/29] Add pre-commit fixes --- .../joint_trajectory_controller/interpolation_methods.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) 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 ce03b8ba32..7b026be667 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -80,8 +80,8 @@ const std::unordered_map InterpolationMethodMa * * \returns The corresponding InterpolationMethod. * - * \note If interpolation_method does not have any corresponding InterpolationMethod (i.e., "Unknown"), - * It defaults to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`. + * \note If interpolation_method does not have any corresponding InterpolationMethod (i.e., + * "Unknown"), It defaults to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`. */ [[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method) { From a256bc15fc3bf0475c41ec62dcc7e36ce50dfde9 Mon Sep 17 00:00:00 2001 From: Mystic Devloper Date: Tue, 25 Nov 2025 11:31:03 +0530 Subject: [PATCH 10/29] Refactor: Changed RCLCPP_INFO to RCLCPP_WARN. --- .../joint_trajectory_controller/interpolation_methods.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 b08d9dd843..e615c37331 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -97,7 +97,7 @@ const std::unordered_map InterpolationMethodMa // Default else { - RCLCPP_INFO( + RCLCPP_WARN( LOGGER, "Unknown interpolation method parameter '%s' was given. Using the default: " "VARIABLE_DEGREE_SPLINE.", From 3a5433364b2a1993b6f80cd6efbea6e632fdc510 Mon Sep 17 00:00:00 2001 From: Mystic Devloper Date: Tue, 25 Nov 2025 12:15:06 +0530 Subject: [PATCH 11/29] Addition: Lowercase conversion function for case-agnostic checking. --- .../interpolation_methods.hpp | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) 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 e615c37331..3c1eb4355e 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -16,6 +16,7 @@ #define JOINT_TRAJECTORY_CONTROLLER__INTERPOLATION_METHODS_HPP_ #include +#include #include #include "rclcpp/rclcpp.hpp" @@ -23,6 +24,21 @@ namespace joint_trajectory_controller { +namespace { + +/// Converts a string to lowercase for case-agnostic checking. +void convert_to_lowercase(std::string& str) +{ + for (char& c : str) { + // C++ std requires the argument passed to std::tolower must be representable as + // unsigned char or equal to EOF. + c = static_cast(std::tolower(static_cast(c))); + } +} + +} // namespace + + /// \brief Setup interpolation_methods' rclcpp::Logger instance. static const rclcpp::Logger LOGGER = rclcpp::get_logger("joint_trajectory_controller.interpolation_methods"); From 1d9fd7439f4877da4e1d7d679a5e77600211618b Mon Sep 17 00:00:00 2001 From: Mystic Devloper Date: Tue, 25 Nov 2025 12:16:46 +0530 Subject: [PATCH 12/29] Refactor: Fixed minor stylistic issues. --- .../joint_trajectory_controller/interpolation_methods.hpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) 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 3c1eb4355e..93100b139b 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -15,8 +15,8 @@ #ifndef JOINT_TRAJECTORY_CONTROLLER__INTERPOLATION_METHODS_HPP_ #define JOINT_TRAJECTORY_CONTROLLER__INTERPOLATION_METHODS_HPP_ -#include #include +#include #include #include "rclcpp/rclcpp.hpp" @@ -24,12 +24,14 @@ namespace joint_trajectory_controller { -namespace { +namespace +{ /// Converts a string to lowercase for case-agnostic checking. void convert_to_lowercase(std::string& str) { - for (char& c : str) { + for (char& c : str) + { // C++ std requires the argument passed to std::tolower must be representable as // unsigned char or equal to EOF. c = static_cast(std::tolower(static_cast(c))); From dcc31afe4b9ecca4f34bf27597fed5ade50651c2 Mon Sep 17 00:00:00 2001 From: Mystic Devloper Date: Tue, 25 Nov 2025 12:42:35 +0530 Subject: [PATCH 13/29] Addition: Added to_string function. --- .../interpolation_methods.hpp | 39 ++++++++++++++++--- 1 file changed, 33 insertions(+), 6 deletions(-) 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 93100b139b..46021e4f47 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -28,14 +28,16 @@ namespace { /// Converts a string to lowercase for case-agnostic checking. -void convert_to_lowercase(std::string& str) +inline std::string convert_to_lowercase(const std::string& str) { - for (char& c : str) + std::string s = str; + for (char& c : s) { // C++ std requires the argument passed to std::tolower must be representable as // unsigned char or equal to EOF. c = static_cast(std::tolower(static_cast(c))); } + return s; } } // namespace @@ -94,17 +96,20 @@ const std::unordered_map InterpolationMethodMa * This function looks up `InterpolationMethodMap` for corresponding `InterpolationMethod` based * on interpolation_method string. * - * \param[in] `interpolation_method` The given interpolation method `string`. + * \param[in] interpolation_method The given interpolation method string. * * \returns The corresponding InterpolationMethod. * - * \note If interpolation_method do not have any corresponding InterpolationMethod (i.e., Unknown), + * \note If interpolation_method does not have any corresponding InterpolationMethod (i.e., "Unknown"), * It defaults to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`. */ -[[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method) +[[nodiscard]] inline InterpolationMethod from_string(const std::string& interpolation_method) { + // Convert to lowercase, so we have an case-agnostic checking. (i.e., None and none, etc are treated same.) + std::string method = convert_to_lowercase(interpolation_method); + // Iterator to InterpolationMethodMap - const auto iterator = InterpolationMethodMap.find(interpolation_method); + const auto iterator = InterpolationMethodMap.find(method); // If interpolation_method exists if (iterator != InterpolationMethodMap.end()) @@ -124,6 +129,28 @@ const std::unordered_map InterpolationMethodMa } } +/** + * \brief Returns corresponding string value for the `InterpolationMethod`. + * This function uses simple switch-case lookup to directly assign string value to + * `InterpolationMethod`. + * + * \param[in] interpolation_method The InterpolationMethod enum value. + * + * \returns The corresponding string. + * + * \note Defaults to return "UNKNOWN". + */ +[[nodiscard]] inline std::string to_string(const InterpolationMethod& interpolation_method) +{ + switch(interpolation_method) + { + case InterpolationMethod::NONE: return "none"; + case InterpolationMethod::VARIABLE_DEGREE_SPLINE: return "splines"; + // Default + default: return "UNKNOWN"; + } +} + } // namespace interpolation_methods } // namespace joint_trajectory_controller From e685997eb0a443f54a1dc4ad560899ef86d476eb Mon Sep 17 00:00:00 2001 From: Surya! Date: Tue, 25 Nov 2025 13:30:33 +0530 Subject: [PATCH 14/29] Fixed pre-commit failures. --- .../interpolation_methods.hpp | 28 +++++++++++-------- 1 file changed, 16 insertions(+), 12 deletions(-) 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 46021e4f47..71ddb152c6 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -28,10 +28,10 @@ namespace { /// Converts a string to lowercase for case-agnostic checking. -inline std::string convert_to_lowercase(const std::string& str) +inline std::string convert_to_lowercase(const std::string & str) { std::string s = str; - for (char& c : s) + for (char & c : s) { // C++ std requires the argument passed to std::tolower must be representable as // unsigned char or equal to EOF. @@ -40,7 +40,7 @@ inline std::string convert_to_lowercase(const std::string& str) return s; } -} // namespace +} // namespace /// \brief Setup interpolation_methods' rclcpp::Logger instance. @@ -100,12 +100,13 @@ const std::unordered_map InterpolationMethodMa * * \returns The corresponding InterpolationMethod. * - * \note If interpolation_method does not have any corresponding InterpolationMethod (i.e., "Unknown"), - * It defaults to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`. + * \note If interpolation_method does not have any corresponding InterpolationMethod + * (i.e., "Unknown"), it defaults to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`. */ -[[nodiscard]] inline InterpolationMethod from_string(const std::string& interpolation_method) +[[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method) { - // Convert to lowercase, so we have an case-agnostic checking. (i.e., None and none, etc are treated same.) + // Convert to lowercase, so we have an case-agnostic checking, + // (i.e., None and none, etc are treated same.) std::string method = convert_to_lowercase(interpolation_method); // Iterator to InterpolationMethodMap @@ -140,14 +141,17 @@ const std::unordered_map InterpolationMethodMa * * \note Defaults to return "UNKNOWN". */ -[[nodiscard]] inline std::string to_string(const InterpolationMethod& interpolation_method) +[[nodiscard]] inline std::string to_string(const InterpolationMethod & interpolation_method) { - switch(interpolation_method) + switch (interpolation_method) { - case InterpolationMethod::NONE: return "none"; - case InterpolationMethod::VARIABLE_DEGREE_SPLINE: return "splines"; + case InterpolationMethod::NONE: + return "none"; + case InterpolationMethod::VARIABLE_DEGREE_SPLINE: + return "splines"; // Default - default: return "UNKNOWN"; + default: + return "UNKNOWN"; } } From d0ba3f16658a5cf01e00ebed5849d8329b3cb2c4 Mon Sep 17 00:00:00 2001 From: Surya! Date: Tue, 25 Nov 2025 13:38:31 +0530 Subject: [PATCH 15/29] Refactor: Fixed whitespace spacing. --- .../joint_trajectory_controller/interpolation_methods.hpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) 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 71ddb152c6..dc4c89b56f 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -40,8 +40,7 @@ inline std::string convert_to_lowercase(const std::string & str) return s; } -} // namespace - +} // namespace /// \brief Setup interpolation_methods' rclcpp::Logger instance. static const rclcpp::Logger LOGGER = @@ -100,7 +99,7 @@ const std::unordered_map InterpolationMethodMa * * \returns The corresponding InterpolationMethod. * - * \note If interpolation_method does not have any corresponding InterpolationMethod + * \note If interpolation_method does not have any corresponding InterpolationMethod * (i.e., "Unknown"), it defaults to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`. */ [[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method) @@ -108,7 +107,7 @@ const std::unordered_map InterpolationMethodMa // Convert to lowercase, so we have an case-agnostic checking, // (i.e., None and none, etc are treated same.) std::string method = convert_to_lowercase(interpolation_method); - + // Iterator to InterpolationMethodMap const auto iterator = InterpolationMethodMap.find(method); From bc536170a7f0a3ac5ccb6dbee2d34d469683d060 Mon Sep 17 00:00:00 2001 From: Mystic Devloper Date: Tue, 25 Nov 2025 15:17:32 +0530 Subject: [PATCH 16/29] Addition: Added warning for unknown value in to_string function. --- .../joint_trajectory_controller/interpolation_methods.hpp | 4 ++++ 1 file changed, 4 insertions(+) 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 dc4c89b56f..f90968dfe7 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -150,6 +150,10 @@ const std::unordered_map InterpolationMethodMa return "splines"; // Default default: + RCLCPP_WARN( + LOGGER, + "Unknown interpolation method enum value was given. Returing default: " + "UNKNOWN"); return "UNKNOWN"; } } From 6a9806164744a0029753c9cb886eff64113e1f62 Mon Sep 17 00:00:00 2001 From: Mystic Devloper Date: Tue, 25 Nov 2025 15:21:07 +0530 Subject: [PATCH 17/29] Addition: Added warning for unknown value in to_string function. --- .../joint_trajectory_controller/interpolation_methods.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 f90968dfe7..2fa6ce328e 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -152,7 +152,7 @@ const std::unordered_map InterpolationMethodMa default: RCLCPP_WARN( LOGGER, - "Unknown interpolation method enum value was given. Returing default: " + "Unknown interpolation method enum value was given. Returning default: " "UNKNOWN"); return "UNKNOWN"; } From 712d588a56913f0b0d99b221f55ad6c9a14f3351 Mon Sep 17 00:00:00 2001 From: Mystic Devloper Date: Tue, 25 Nov 2025 15:28:36 +0530 Subject: [PATCH 18/29] Addition: Added warning for unknown value in to_string function. --- .../joint_trajectory_controller/interpolation_methods.hpp | 4 ++++ 1 file changed, 4 insertions(+) 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 dc4c89b56f..2fa6ce328e 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -150,6 +150,10 @@ const std::unordered_map InterpolationMethodMa return "splines"; // Default default: + RCLCPP_WARN( + LOGGER, + "Unknown interpolation method enum value was given. Returning default: " + "UNKNOWN"); return "UNKNOWN"; } } From 6085b05de2f732a48787efa88efee953cc056b78 Mon Sep 17 00:00:00 2001 From: Surya Date: Tue, 25 Nov 2025 16:36:44 +0530 Subject: [PATCH 19/29] Doc: Fixed grammatic mistakes and polished the documentation. --- .../interpolation_methods.hpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) 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 2fa6ce328e..651bfdf097 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -66,9 +66,9 @@ enum class InterpolationMethod /** * \brief Uses a variable-degree spline interpolation. * The degree of the spline is determined dynamically based on the number of - * available deriviatives. This provides a smooth, continuous curve between data points. + * available derivatives. This provides a smooth, continuous curve between data points. * - * Based on available deriviatives, it uses following degree interpolation, + * Based on available derivatives, it uses the following degree interpolation, * 1. Neither velocity nor acceleration is available: `Linear Interpolation`. * 2. Velocity is available, but acceleration is not available: `Cubic Spline Interpolation`. * 3. Both velocity and acceleration is available: `Quintic Spline Interpolation`. @@ -78,13 +78,13 @@ enum class InterpolationMethod /** * \brief The default interpolation method is set to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`. - * As, it provides most realistic, jerk-free and smooth motion. + * As it provides the most realistic, jerk-free and smooth motion. */ const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_DEGREE_SPLINE; /** * \brief Maps `InterpolationMethod` enum values to their string identifiers. - * This constant map is used to look up the InterpolationMethod for a given + * This constant map is used for the lookup of the InterpolationMethod for a given * string (e.g., "splines" for `VARIABLE_DEGREE_SPLINE`). */ const std::unordered_map InterpolationMethodMap( @@ -104,7 +104,7 @@ const std::unordered_map InterpolationMethodMa */ [[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method) { - // Convert to lowercase, so we have an case-agnostic checking, + // Convert to lowercase, so we have a case-agnostic checking, // (i.e., None and none, etc are treated same.) std::string method = convert_to_lowercase(interpolation_method); From 84f4cac6bf7102148040bc866340db01d8ef0fe6 Mon Sep 17 00:00:00 2001 From: Surya! Date: Wed, 26 Nov 2025 09:22:37 +0530 Subject: [PATCH 20/29] Remove: Removed helper convert_to_lowercase function. --- .../interpolation_methods.hpp | 20 +------------------ 1 file changed, 1 insertion(+), 19 deletions(-) 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 651bfdf097..804b831d85 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -15,33 +15,15 @@ #ifndef JOINT_TRAJECTORY_CONTROLLER__INTERPOLATION_METHODS_HPP_ #define JOINT_TRAJECTORY_CONTROLLER__INTERPOLATION_METHODS_HPP_ -#include #include #include +#include "hardware_interface/lexical_casts.hpp" #include "rclcpp/rclcpp.hpp" namespace joint_trajectory_controller { -namespace -{ - -/// Converts a string to lowercase for case-agnostic checking. -inline std::string convert_to_lowercase(const std::string & str) -{ - std::string s = str; - for (char & c : s) - { - // C++ std requires the argument passed to std::tolower must be representable as - // unsigned char or equal to EOF. - c = static_cast(std::tolower(static_cast(c))); - } - return s; -} - -} // namespace - /// \brief Setup interpolation_methods' rclcpp::Logger instance. static const rclcpp::Logger LOGGER = rclcpp::get_logger("joint_trajectory_controller.interpolation_methods"); From fcb78325dc3899efd5be1e5960ba5ca25f5b3594 Mon Sep 17 00:00:00 2001 From: Surya! Date: Wed, 26 Nov 2025 09:36:45 +0530 Subject: [PATCH 21/29] Refactor: Refactored from_string to directly use string comparision. --- .../interpolation_methods.hpp | 86 +++++++++---------- 1 file changed, 39 insertions(+), 47 deletions(-) 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 804b831d85..a062446630 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -64,53 +64,6 @@ enum class InterpolationMethod */ const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_DEGREE_SPLINE; -/** - * \brief Maps `InterpolationMethod` enum values to their string identifiers. - * This constant map is used for the lookup of the InterpolationMethod for a given - * string (e.g., "splines" for `VARIABLE_DEGREE_SPLINE`). - */ -const std::unordered_map InterpolationMethodMap( - {{"none", InterpolationMethod::NONE}, {"splines", InterpolationMethod::VARIABLE_DEGREE_SPLINE}}); - -/** - * \brief Creates a `InterpolationMethod` enum class value from a string. - * This function looks up `InterpolationMethodMap` for corresponding `InterpolationMethod` based - * on interpolation_method string. - * - * \param[in] interpolation_method The given interpolation method string. - * - * \returns The corresponding InterpolationMethod. - * - * \note If interpolation_method does not have any corresponding InterpolationMethod - * (i.e., "Unknown"), it defaults to `InterpolationMethod::VARIABLE_DEGREE_SPLINE`. - */ -[[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method) -{ - // Convert to lowercase, so we have a case-agnostic checking, - // (i.e., None and none, etc are treated same.) - std::string method = convert_to_lowercase(interpolation_method); - - // Iterator to InterpolationMethodMap - const auto iterator = InterpolationMethodMap.find(method); - - // If interpolation_method exists - if (iterator != InterpolationMethodMap.end()) - { - // Return corresponding `InterpolationMethod` - return iterator->second; - } - // Default - else - { - RCLCPP_WARN( - LOGGER, - "Unknown interpolation method parameter '%s' was given. Using the default: " - "VARIABLE_DEGREE_SPLINE.", - interpolation_method.c_str()); - return 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 @@ -140,6 +93,45 @@ const std::unordered_map InterpolationMethodMa } } +/** + * \brief Creates a `InterpolationMethod` enum class value from a string. + * This function directly looks up for corresponding `InterpolationMethod` based + * on interpolation_method string (case-agnostic). + * + * \param[in] interpolation_method The given interpolation method string. + * + * \returns The corresponding InterpolationMethod. + * + * \note If interpolation_method does not have any corresponding InterpolationMethod + * (i.e., "Unknown"), it defaults to `DEFAULT_INTERPOLATION`. + */ +[[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method) +{ + // Convert to lowercase, so we have a case-agnostic checking, + // (i.e., "None, NONE, and none" are treated same.) + std::string method = ::hardware_interface::to_lower_case(interpolation_method); + + if (method == "none") + { + return InterpolationMethod::NONE; + } + else if (method == "splines") + { + return InterpolationMethod::VARIABLE_DEGREE_SPLINE; + } + // Default + else + { + RCLCPP_WARN( + LOGGER, + "Unknown interpolation method parameter '%s' was given. Using the default: " + "DEFAULT_INTERPOLATION (%s).", + interpolation_method.c_str(), + to_string(DEFAULT_INTERPOLATION).c_str()); + return DEFAULT_INTERPOLATION; + } +} + } // namespace interpolation_methods } // namespace joint_trajectory_controller From 185e9d1d68b11e62116ae7b69d4ca39143eb2bf0 Mon Sep 17 00:00:00 2001 From: Surya! Date: Wed, 26 Nov 2025 09:59:36 +0530 Subject: [PATCH 22/29] Refactor: Fixed pre-commit stylistic issues. --- .../joint_trajectory_controller/interpolation_methods.hpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) 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 a062446630..fdd9e53fe1 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -126,8 +126,7 @@ const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_ LOGGER, "Unknown interpolation method parameter '%s' was given. Using the default: " "DEFAULT_INTERPOLATION (%s).", - interpolation_method.c_str(), - to_string(DEFAULT_INTERPOLATION).c_str()); + interpolation_method.c_str(), to_string(DEFAULT_INTERPOLATION).c_str()); return DEFAULT_INTERPOLATION; } } From bc81c92b6dd61d660d547944179daa51d7ad336a Mon Sep 17 00:00:00 2001 From: Surya Date: Fri, 28 Nov 2025 16:11:05 +0530 Subject: [PATCH 23/29] Refactor: Readded InterpolationMethodMap, and deprecated it, in favour of simple direct lookup methods. --- .../interpolation_methods.hpp | 10 ++++++++++ 1 file changed, 10 insertions(+) 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 fdd9e53fe1..6144155c94 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -64,6 +64,16 @@ 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 is deprecated. Use the direct lookup methods instead.")]] +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 From 9f4309a17f0e19c2857e5f7560dc4f6d44709942 Mon Sep 17 00:00:00 2001 From: TheDevMystic Date: Sat, 29 Nov 2025 10:14:46 +0530 Subject: [PATCH 24/29] Refactor: Fixed documentations. --- .../interpolation_methods.hpp | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) 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 6144155c94..ce67054b65 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -42,6 +42,9 @@ enum class InterpolationMethod * \brief No interpolation is performed. * This is typically used when data points are discrete and should not be * connected by a curve. + * + * It returns the initial point until the time for the first trajectory data + * point is reached. Then, it simply takes the next given datapoint. */ NONE, @@ -51,9 +54,13 @@ enum class InterpolationMethod * available derivatives. This provides a smooth, continuous curve between data points. * * Based on available derivatives, it uses the following degree interpolation, - * 1. Neither velocity nor acceleration is available: `Linear Interpolation`. - * 2. Velocity is available, but acceleration is not available: `Cubic Spline Interpolation`. - * 3. Both velocity and acceleration is available: `Quintic Spline Interpolation`. + * 1. If only position is available: `Linear Interpolation`. + * 2. If position, and velocity are available: `Cubic Spline Interpolation`. + * 3. If position, velocity, and acceleration is available: `Quintic Spline Interpolation`. + * + * \note + * `Linear Interpolation` is discouraged, due to it yields trajectories with discontinuous + * velocities at the waypoints. */ VARIABLE_DEGREE_SPLINE }; @@ -70,7 +77,9 @@ const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_ * @deprecated This map is deprecated. Use the direct lookup methods instead. * (Original use: Converting strings into the InterpolationMethod). */ -[[deprecated("InterpolationMethodMap is deprecated. Use the direct lookup methods instead.")]] +[[deprecated( + "InterpolationMethodMap is expected to be removed in future iterations of JTC. + Instead, use the direct lookup methods instead.")]] const std::unordered_map InterpolationMethodMap( {{"none", InterpolationMethod::NONE}, {"splines", InterpolationMethod::VARIABLE_DEGREE_SPLINE}}); From e07b712ac2d54d78586e03f385ee54d694b11b27 Mon Sep 17 00:00:00 2001 From: TheDevMystic Date: Sat, 29 Nov 2025 10:18:10 +0530 Subject: [PATCH 25/29] Refactor: Fixed documentations. --- .../joint_trajectory_controller/interpolation_methods.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) 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 ce67054b65..39b9532847 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -78,8 +78,8 @@ const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_ * (Original use: Converting strings into the InterpolationMethod). */ [[deprecated( - "InterpolationMethodMap is expected to be removed in future iterations of JTC. - Instead, use the direct lookup methods instead.")]] + "InterpolationMethodMap is expected to be removed in future iterations of JTC. " + "Instead, use the direct lookup methods instead.")]] const std::unordered_map InterpolationMethodMap( {{"none", InterpolationMethod::NONE}, {"splines", InterpolationMethod::VARIABLE_DEGREE_SPLINE}}); From ce2f2db28193191d8091b36ffe0224fd509678de Mon Sep 17 00:00:00 2001 From: TheDevMystic Date: Sat, 29 Nov 2025 10:58:19 +0530 Subject: [PATCH 26/29] Doc: Fixed grammatic mistakes. --- .../joint_trajectory_controller/interpolation_methods.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 39b9532847..447292354c 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -56,7 +56,7 @@ enum class InterpolationMethod * Based on available derivatives, it uses the following degree interpolation, * 1. If only position is available: `Linear Interpolation`. * 2. If position, and velocity are available: `Cubic Spline Interpolation`. - * 3. If position, velocity, and acceleration is available: `Quintic Spline Interpolation`. + * 3. If position, velocity, and acceleration are available: `Quintic Spline Interpolation`. * * \note * `Linear Interpolation` is discouraged, due to it yields trajectories with discontinuous From 7f2790f3c59332d0a9ba198943e32ebabf61ae08 Mon Sep 17 00:00:00 2001 From: Surya! Date: Sat, 29 Nov 2025 13:16:42 +0530 Subject: [PATCH 27/29] Doc: Fixed deprecated message. --- .../joint_trajectory_controller/interpolation_methods.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 447292354c..2394b28927 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -79,7 +79,7 @@ const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_ */ [[deprecated( "InterpolationMethodMap is expected to be removed in future iterations of JTC. " - "Instead, use the direct lookup methods instead.")]] + "Instead, use the direct lookup methods.")]] const std::unordered_map InterpolationMethodMap( {{"none", InterpolationMethod::NONE}, {"splines", InterpolationMethod::VARIABLE_DEGREE_SPLINE}}); From 8af08338d96d403c6a721d492271ca3661f1b7f1 Mon Sep 17 00:00:00 2001 From: Surya! Date: Mon, 1 Dec 2025 07:28:31 +0530 Subject: [PATCH 28/29] Doc: Fixed wording of depreciation of InterpolationMethodMap. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Christoph Fröhlich --- .../joint_trajectory_controller/interpolation_methods.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 2394b28927..bf075100e5 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -78,7 +78,7 @@ const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_ * (Original use: Converting strings into the InterpolationMethod). */ [[deprecated( - "InterpolationMethodMap is expected to be removed in future iterations of JTC. " + "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}}); From db8f06a73ed6d6a30ff44f36b82bd8b00525b8c6 Mon Sep 17 00:00:00 2001 From: Surya! Date: Mon, 1 Dec 2025 09:22:38 +0530 Subject: [PATCH 29/29] Doc: Removed Linear Interpolation Advise. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Christoph Fröhlich --- .../joint_trajectory_controller/interpolation_methods.hpp | 4 ---- 1 file changed, 4 deletions(-) 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 bf075100e5..f4bfb4f592 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/interpolation_methods.hpp @@ -57,10 +57,6 @@ enum class InterpolationMethod * 1. If only position is available: `Linear Interpolation`. * 2. If position, and velocity are available: `Cubic Spline Interpolation`. * 3. If position, velocity, and acceleration are available: `Quintic Spline Interpolation`. - * - * \note - * `Linear Interpolation` is discouraged, due to it yields trajectories with discontinuous - * velocities at the waypoints. */ VARIABLE_DEGREE_SPLINE };