ros2_control - iron
Loading...
Searching...
No Matches
validate_jtc_parameters.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__VALIDATE_JTC_PARAMETERS_HPP_
16#define JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_
17
18#include <string>
19#include <vector>
20
21#include "rclcpp/parameter.hpp"
22#include "rsl/algorithm.hpp"
23#include "tl_expected/expected.hpp"
24
26{
27tl::expected<void, std::string> command_interface_type_combinations(
28 rclcpp::Parameter const & parameter)
29{
30 auto const & interface_types = parameter.as_string_array();
31
32 // Check if command interfaces combination is valid. Valid combinations are:
33 // 1. effort
34 // 2. velocity
35 // 2. position [velocity, [acceleration]]
36
37 if (
38 rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
39 interface_types.size() > 1 &&
40 !rsl::contains<std::vector<std::string>>(interface_types, "position"))
41 {
42 return tl::make_unexpected(
43 "'velocity' command interface can be used either alone or 'position' "
44 "command interface has to be present");
45 }
46
47 if (
48 rsl::contains<std::vector<std::string>>(interface_types, "acceleration") &&
49 (!rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
50 !rsl::contains<std::vector<std::string>>(interface_types, "position")))
51 {
52 return tl::make_unexpected(
53 "'acceleration' command interface can only be used if 'velocity' and "
54 "'position' command interfaces are present");
55 }
56
57 if (
58 rsl::contains<std::vector<std::string>>(interface_types, "effort") &&
59 interface_types.size() > 1)
60 {
61 return tl::make_unexpected("'effort' command interface has to be used alone");
62 }
63
64 return {};
65}
66
67tl::expected<void, std::string> state_interface_type_combinations(
68 rclcpp::Parameter const & parameter)
69{
70 auto const & interface_types = parameter.as_string_array();
71
72 // Valid combinations are
73 // 1. position [velocity, [acceleration]]
74
75 if (
76 rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
77 !rsl::contains<std::vector<std::string>>(interface_types, "position"))
78 {
79 return tl::make_unexpected(
80 "'velocity' state interface cannot be used if 'position' interface "
81 "is missing.");
82 }
83
84 if (
85 rsl::contains<std::vector<std::string>>(interface_types, "acceleration") &&
86 (!rsl::contains<std::vector<std::string>>(interface_types, "position") ||
87 !rsl::contains<std::vector<std::string>>(interface_types, "velocity")))
88 {
89 return tl::make_unexpected(
90 "'acceleration' state interface cannot be used if 'position' and 'velocity' "
91 "interfaces are not present.");
92 }
93
94 return {};
95}
96
97} // namespace joint_trajectory_controller
98
99#endif // JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_
Definition interpolation_methods.hpp:24