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();
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"))
43 return tl::make_unexpected(
44 "'velocity' command interface can be used either alone or 'position' "
45 "command interface has to be present");
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")))
53 return tl::make_unexpected(
54 "'acceleration' command interface can only be used if 'velocity' and "
55 "'position' command interfaces are present");
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"))))
64 return tl::make_unexpected(
65 "'effort' command interface has to be used alone or with a 'position' interface");
71tl::expected<void, std::string> state_interface_type_combinations(
72 rclcpp::Parameter
const & parameter)
74 auto const & interface_types = parameter.as_string_array();
80 rsl::contains<std::vector<std::string>>(interface_types,
"velocity") &&
81 !rsl::contains<std::vector<std::string>>(interface_types,
"position"))
83 return tl::make_unexpected(
84 "'velocity' state interface cannot be used if 'position' interface "
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")))
93 return tl::make_unexpected(
94 "'acceleration' state interface cannot be used if 'position' and 'velocity' "
95 "interfaces are not present.");
Definition interpolation_methods.hpp:24