ros2_control - rolling
Loading...
Searching...
No Matches
interpolation_methods.hpp
1// Copyright (c) 2022 ros2_control Development Team
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef JOINT_TRAJECTORY_CONTROLLER__INTERPOLATION_METHODS_HPP_
16#define JOINT_TRAJECTORY_CONTROLLER__INTERPOLATION_METHODS_HPP_
17
18#include <string>
19#include <unordered_map>
20
21#include "hardware_interface/lexical_casts.hpp"
22#include "rclcpp/rclcpp.hpp"
23
25{
26
28static const rclcpp::Logger LOGGER =
29 rclcpp::get_logger("joint_trajectory_controller.interpolation_methods");
30
31namespace interpolation_methods
32{
33
39enum class InterpolationMethod
40{
49 NONE,
50
61 VARIABLE_DEGREE_SPLINE
62};
63
68const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_DEGREE_SPLINE;
69
81[[nodiscard]] inline std::string to_string(const InterpolationMethod & interpolation_method)
82{
83 switch (interpolation_method)
84 {
85 case InterpolationMethod::NONE:
86 return "none";
87 case InterpolationMethod::VARIABLE_DEGREE_SPLINE:
88 return "splines";
89 // Default
90 default:
91 RCLCPP_WARN(
92 LOGGER,
93 "Unknown interpolation method enum value was given. Returning default: "
94 "UNKNOWN");
95 return "UNKNOWN";
96 }
97}
98
111[[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method)
112{
113 // Convert to lowercase, so we have a case-agnostic checking,
114 // (i.e., "None, NONE, and none" are treated same.)
115 std::string method = ::hardware_interface::to_lower_case(interpolation_method);
116
117 if (method == "none")
118 {
119 return InterpolationMethod::NONE;
120 }
121 else if (method == "splines")
122 {
123 return InterpolationMethod::VARIABLE_DEGREE_SPLINE;
124 }
125 // Default
126 else
127 {
128 RCLCPP_WARN(
129 LOGGER,
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;
134 }
135}
136
137} // namespace interpolation_methods
138} // namespace joint_trajectory_controller
139
140#endif // JOINT_TRAJECTORY_CONTROLLER__INTERPOLATION_METHODS_HPP_
std::string to_lower_case(const std::string &string)
Convert a string to lower case.
Definition lexical_casts.cpp:103
Definition interpolation_methods.hpp:25