15#ifndef JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_
16#define JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_
21#include "parameter_traits/parameter_traits.hpp"
22#include "rclcpp/parameter.hpp"
23#include "rsl/algorithm.hpp"
24#include "tl_expected/expected.hpp"
28tl::expected<void, std::string> command_interface_type_combinations(
29 rclcpp::Parameter
const & parameter)
31 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)
62 return tl::make_unexpected(
"'effort' command interface has to be used alone");
68tl::expected<void, std::string> state_interface_type_combinations(
69 rclcpp::Parameter
const & parameter)
71 auto const & interface_types = parameter.as_string_array();
77 rsl::contains<std::vector<std::string>>(interface_types,
"velocity") &&
78 !rsl::contains<std::vector<std::string>>(interface_types,
"position"))
80 return tl::make_unexpected(
81 "'velocity' state interface cannot be used if 'position' interface "
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")))
90 return tl::make_unexpected(
91 "'acceleration' state interface cannot be used if 'position' and 'velocity' "
92 "interfaces are not present.");
Definition interpolation_methods.hpp:24