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
76[[deprecated(
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}});
81
93[[nodiscard]] inline std::string to_string(const InterpolationMethod & interpolation_method)
94{
95 switch (interpolation_method)
96 {
97 case InterpolationMethod::NONE:
98 return "none";
99 case InterpolationMethod::VARIABLE_DEGREE_SPLINE:
100 return "splines";
101 // Default
102 default:
103 RCLCPP_WARN(
104 LOGGER,
105 "Unknown interpolation method enum value was given. Returning default: "
106 "UNKNOWN");
107 return "UNKNOWN";
108 }
109}
110
123[[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method)
124{
125 // Convert to lowercase, so we have a case-agnostic checking,
126 // (i.e., "None, NONE, and none" are treated same.)
127 std::string method = ::hardware_interface::to_lower_case(interpolation_method);
128
129 if (method == "none")
130 {
131 return InterpolationMethod::NONE;
132 }
133 else if (method == "splines")
134 {
135 return InterpolationMethod::VARIABLE_DEGREE_SPLINE;
136 }
137 // Default
138 else
139 {
140 RCLCPP_WARN(
141 LOGGER,
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;
146 }
147}
148
149} // namespace interpolation_methods
150} // namespace joint_trajectory_controller
151
152#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