|
20 | 20 |
|
21 | 21 | #include "rclcpp/parameter.hpp" |
22 | 22 | #include "rsl/algorithm.hpp" |
23 | | -#include "tl_expected/expected.hpp" |
| 23 | +#include "tl/expected.hpp" |
24 | 24 |
|
25 | 25 | namespace joint_trajectory_controller |
26 | 26 | { |
27 | | - |
28 | | -/** |
29 | | - * \brief Validate command interface type combinations for joint trajectory controller. |
30 | | - * |
31 | | - * \param[in] parameter The rclcpp parameter containing the command interface types. |
32 | | - * \return tl::expected<void, std::string> An empty expected on success, or an error message on |
33 | | - * failure. |
34 | | - */ |
35 | 27 | tl::expected<void, std::string> command_interface_type_combinations( |
36 | | - rclcpp::Parameter const & parameter); |
37 | | - |
38 | | -/** |
39 | | - * \brief Validate state interface type combinations for joint trajectory controller. |
40 | | - * |
41 | | - * \param[in] parameter The rclcpp parameter containing the state interface types. |
42 | | - * \return tl::expected<void, std::string> An empty expected on success, or an error message on |
43 | | - * failure. |
44 | | - */ |
| 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 | + |
45 | 71 | tl::expected<void, std::string> state_interface_type_combinations( |
46 | | - rclcpp::Parameter const & parameter); |
| 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 | +} |
47 | 100 |
|
48 | 101 | } // namespace joint_trajectory_controller |
49 | 102 |
|
|
0 commit comments