ros2_control - humble
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 "parameter_traits/parameter_traits.hpp"
22#include "rclcpp/parameter.hpp"
23#include "rsl/algorithm.hpp"
24#include "tl_expected/expected.hpp"
25
27{
28tl::expected<void, std::string> command_interface_type_combinations(
29 rclcpp::Parameter const & parameter)
30{
31 auto const & interface_types = parameter.as_string_array();
32
33 // Check if command interfaces combination is valid. Valid combinations are:
34 // 1. effort
35 // 2. velocity
36 // 2. position [velocity, [acceleration]]
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 {
62 return tl::make_unexpected("'effort' command interface has to be used alone");
63 }
64
65 return {};
66}
67
68tl::expected<void, std::string> state_interface_type_combinations(
69 rclcpp::Parameter const & parameter)
70{
71 auto const & interface_types = parameter.as_string_array();
72
73 // Valid combinations are
74 // 1. position [velocity, [acceleration]]
75
76 if (
77 rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
78 !rsl::contains<std::vector<std::string>>(interface_types, "position"))
79 {
80 return tl::make_unexpected(
81 "'velocity' state interface cannot be used if 'position' interface "
82 "is missing.");
83 }
84
85 if (
86 rsl::contains<std::vector<std::string>>(interface_types, "acceleration") &&
87 (!rsl::contains<std::vector<std::string>>(interface_types, "position") ||
88 !rsl::contains<std::vector<std::string>>(interface_types, "velocity")))
89 {
90 return tl::make_unexpected(
91 "'acceleration' state interface cannot be used if 'position' and 'velocity' "
92 "interfaces are not present.");
93 }
94
95 return {};
96}
97
98} // namespace joint_trajectory_controller
99
100#endif // JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_
Definition interpolation_methods.hpp:24