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;
81[[nodiscard]]
inline std::string to_string(
const InterpolationMethod & interpolation_method)
83 switch (interpolation_method)
85 case InterpolationMethod::NONE:
87 case InterpolationMethod::VARIABLE_DEGREE_SPLINE:
93 "Unknown interpolation method enum value was given. Returning default: "
111[[nodiscard]]
inline InterpolationMethod from_string(
const std::string & interpolation_method)
117 if (method ==
"none")
119 return InterpolationMethod::NONE;
121 else if (method ==
"splines")
123 return InterpolationMethod::VARIABLE_DEGREE_SPLINE;
130 "Unknown interpolation method parameter '%s' was given. Using the default: "
131 "DEFAULT_INTERPOLATION (%s).",
132 interpolation_method.c_str(), to_string(DEFAULT_INTERPOLATION).c_str());
133 return DEFAULT_INTERPOLATION;