ros2_control - jazzy
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 // 3. position [velocity, [acceleration]]
36 // 4. position, effort
37
38 if (
39 rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
40 interface_types.size() > 1 &&
41 !rsl::contains<std::vector<std::string>>(interface_types, "position"))
42 {
43 return tl::make_unexpected(
44 "'velocity' command interface can be used either alone or 'position' "
45 "command interface has to be present");
46 }
47
48 if (
49 rsl::contains<std::vector<std::string>>(interface_types, "acceleration") &&
50 (!rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
51 !rsl::contains<std::vector<std::string>>(interface_types, "position")))
52 {
53 return tl::make_unexpected(
54 "'acceleration' command interface can only be used if 'velocity' and "
55 "'position' command interfaces are present");
56 }
57
58 if (
59 rsl::contains<std::vector<std::string>>(interface_types, "effort") &&
60 !(interface_types.size() == 1 ||
61 (interface_types.size() == 2 &&
62 rsl::contains<std::vector<std::string>>(interface_types, "position"))))
63 {
64 return tl::make_unexpected(
65 "'effort' command interface has to be used alone or with a 'position' interface");
66 }
67
68 return {};
69}
70
71tl::expected<void, std::string> state_interface_type_combinations(
72 rclcpp::Parameter const & parameter)
73{
74 auto const & interface_types = parameter.as_string_array();
75
76 // Valid combinations are
77 // 1. position [velocity, [acceleration]]
78
79 if (
80 rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
81 !rsl::contains<std::vector<std::string>>(interface_types, "position"))
82 {
83 return tl::make_unexpected(
84 "'velocity' state interface cannot be used if 'position' interface "
85 "is missing.");
86 }
87
88 if (
89 rsl::contains<std::vector<std::string>>(interface_types, "acceleration") &&
90 (!rsl::contains<std::vector<std::string>>(interface_types, "position") ||
91 !rsl::contains<std::vector<std::string>>(interface_types, "velocity")))
92 {
93 return tl::make_unexpected(
94 "'acceleration' state interface cannot be used if 'position' and 'velocity' "
95 "interfaces are not present.");
96 }
97
98 return {};
99}
100
101} // namespace joint_trajectory_controller
102
103#endif // JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_
Definition interpolation_methods.hpp:24