Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,11 @@
#include <string>
#include <vector>

#include "parameter_traits/parameter_traits.hpp"
#include "rclcpp/parameter.hpp"
#include "rsl/algorithm.hpp"
#include "tl_expected/expected.hpp"

namespace parameter_traits
namespace joint_trajectory_controller
{
tl::expected<void, std::string> command_interface_type_combinations(
rclcpp::Parameter const & parameter)
Expand Down Expand Up @@ -95,6 +94,6 @@ tl::expected<void, std::string> state_interface_type_combinations(
return {};
}

} // namespace parameter_traits
} // namespace joint_trajectory_controller

#endif // JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ joint_trajectory_controller:
validation: {
unique<>: null,
subset_of<>: [["position", "velocity", "acceleration", "effort",]],
command_interface_type_combinations: null,
"joint_trajectory_controller::command_interface_type_combinations": null,
}
}
state_interfaces: {
Expand All @@ -32,7 +32,7 @@ joint_trajectory_controller:
validation: {
unique<>: null,
subset_of<>: [["position", "velocity", "acceleration",]],
state_interface_type_combinations: null,
"joint_trajectory_controller::state_interface_type_combinations": null,
}
}
allow_partial_joints_goal: {
Expand Down