15#ifndef JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_
16#define JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_
21#include "rclcpp/parameter.hpp"
22#include "rsl/algorithm.hpp"
23#include "tl_expected/expected.hpp"
27tl::expected<void, std::string> command_interface_type_combinations(
28 rclcpp::Parameter
const & parameter)
30 auto const & interface_types = parameter.as_string_array();
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"))
42 return tl::make_unexpected(
43 "'velocity' command interface can be used either alone or 'position' "
44 "command interface has to be present");
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")))
52 return tl::make_unexpected(
53 "'acceleration' command interface can only be used if 'velocity' and "
54 "'position' command interfaces are present");
58 rsl::contains<std::vector<std::string>>(interface_types,
"effort") &&
59 interface_types.size() > 1)
61 return tl::make_unexpected(
"'effort' command interface has to be used alone");
67tl::expected<void, std::string> state_interface_type_combinations(
68 rclcpp::Parameter
const & parameter)
70 auto const & interface_types = parameter.as_string_array();
76 rsl::contains<std::vector<std::string>>(interface_types,
"velocity") &&
77 !rsl::contains<std::vector<std::string>>(interface_types,
"position"))
79 return tl::make_unexpected(
80 "'velocity' state interface cannot be used if 'position' interface "
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")))
89 return tl::make_unexpected(
90 "'acceleration' state interface cannot be used if 'position' and 'velocity' "
91 "interfaces are not present.");
Definition interpolation_methods.hpp:24