25static const rclcpp::Logger LOGGER =
26 rclcpp::get_logger(
"joint_trajectory_controller.interpolation_methods");
28namespace interpolation_methods
30enum class InterpolationMethod
33 VARIABLE_DEGREE_SPLINE
36const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_DEGREE_SPLINE;
38const std::unordered_map<InterpolationMethod, std::string> InterpolationMethodMap(
39 {{InterpolationMethod::NONE,
"none"}, {InterpolationMethod::VARIABLE_DEGREE_SPLINE,
"splines"}});
41[[nodiscard]]
inline InterpolationMethod from_string(
const std::string & interpolation_method)
43 if (interpolation_method.compare(InterpolationMethodMap.at(InterpolationMethod::NONE)) == 0)
45 return InterpolationMethod::NONE;
48 interpolation_method.compare(
49 InterpolationMethodMap.at(InterpolationMethod::VARIABLE_DEGREE_SPLINE)) == 0)
51 return InterpolationMethod::VARIABLE_DEGREE_SPLINE;
58 "No interpolation method parameter was given. Using the default, VARIABLE_DEGREE_SPLINE.");
59 return InterpolationMethod::VARIABLE_DEGREE_SPLINE;