28static const rclcpp::Logger LOGGER =
29 rclcpp::get_logger(
"joint_trajectory_controller.interpolation_methods");
31namespace interpolation_methods
39enum class InterpolationMethod
61 VARIABLE_DEGREE_SPLINE
68const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_DEGREE_SPLINE;
77 "InterpolationMethodMap will be removed in future releases. "
78 "Instead, use the direct lookup methods.")]]
79const std::unordered_map<std::string, InterpolationMethod> InterpolationMethodMap(
80 {{
"none", InterpolationMethod::NONE}, {
"splines", InterpolationMethod::VARIABLE_DEGREE_SPLINE}});
93[[nodiscard]]
inline std::string to_string(
const InterpolationMethod & interpolation_method)
95 switch (interpolation_method)
97 case InterpolationMethod::NONE:
99 case InterpolationMethod::VARIABLE_DEGREE_SPLINE:
105 "Unknown interpolation method enum value was given. Returning default: "
123[[nodiscard]]
inline InterpolationMethod from_string(
const std::string & interpolation_method)
129 if (method ==
"none")
131 return InterpolationMethod::NONE;
133 else if (method ==
"splines")
135 return InterpolationMethod::VARIABLE_DEGREE_SPLINE;
142 "Unknown interpolation method parameter '%s' was given. Using the default: "
143 "DEFAULT_INTERPOLATION (%s).",
144 interpolation_method.c_str(), to_string(DEFAULT_INTERPOLATION).c_str());
145 return DEFAULT_INTERPOLATION;