ros2_control - humble
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 "rclcpp/rclcpp.hpp"
22
24{
25static const rclcpp::Logger LOGGER =
26 rclcpp::get_logger("joint_trajectory_controller.interpolation_methods");
27
28namespace interpolation_methods
29{
30enum class InterpolationMethod
31{
32 NONE,
33 VARIABLE_DEGREE_SPLINE
34};
35
36const InterpolationMethod DEFAULT_INTERPOLATION = InterpolationMethod::VARIABLE_DEGREE_SPLINE;
37
38const std::unordered_map<InterpolationMethod, std::string> InterpolationMethodMap(
39 {{InterpolationMethod::NONE, "none"}, {InterpolationMethod::VARIABLE_DEGREE_SPLINE, "splines"}});
40
41[[nodiscard]] inline InterpolationMethod from_string(const std::string & interpolation_method)
42{
43 if (interpolation_method.compare(InterpolationMethodMap.at(InterpolationMethod::NONE)) == 0)
44 {
45 return InterpolationMethod::NONE;
46 }
47 else if (
48 interpolation_method.compare(
49 InterpolationMethodMap.at(InterpolationMethod::VARIABLE_DEGREE_SPLINE)) == 0)
50 {
51 return InterpolationMethod::VARIABLE_DEGREE_SPLINE;
52 }
53 // Default
54 else
55 {
56 RCLCPP_INFO_STREAM(
57 LOGGER,
58 "No interpolation method parameter was given. Using the default, VARIABLE_DEGREE_SPLINE.");
59 return InterpolationMethod::VARIABLE_DEGREE_SPLINE;
60 }
61}
62} // namespace interpolation_methods
63} // namespace joint_trajectory_controller
64
65#endif // JOINT_TRAJECTORY_CONTROLLER__INTERPOLATION_METHODS_HPP_
Definition interpolation_methods.hpp:24