Skip to content

Commit e49c540

Browse files
christophfroehlichbmagyar
authored andcommitted
Fix namespace for parameter traits(#703)
1 parent 88c3463 commit e49c540

File tree

2 files changed

+4
-5
lines changed

2 files changed

+4
-5
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -18,12 +18,11 @@
1818
#include <string>
1919
#include <vector>
2020

21-
#include "parameter_traits/parameter_traits.hpp"
2221
#include "rclcpp/parameter.hpp"
2322
#include "rsl/algorithm.hpp"
2423
#include "tl_expected/expected.hpp"
2524

26-
namespace parameter_traits
25+
namespace joint_trajectory_controller
2726
{
2827
tl::expected<void, std::string> command_interface_type_combinations(
2928
rclcpp::Parameter const & parameter)
@@ -95,6 +94,6 @@ tl::expected<void, std::string> state_interface_type_combinations(
9594
return {};
9695
}
9796

98-
} // namespace parameter_traits
97+
} // namespace joint_trajectory_controller
9998

10099
#endif // JOINT_TRAJECTORY_CONTROLLER__VALIDATE_JTC_PARAMETERS_HPP_

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ joint_trajectory_controller:
2222
validation: {
2323
unique<>: null,
2424
subset_of<>: [["position", "velocity", "acceleration", "effort",]],
25-
command_interface_type_combinations: null,
25+
"joint_trajectory_controller::command_interface_type_combinations": null,
2626
}
2727
}
2828
state_interfaces: {
@@ -32,7 +32,7 @@ joint_trajectory_controller:
3232
validation: {
3333
unique<>: null,
3434
subset_of<>: [["position", "velocity", "acceleration",]],
35-
state_interface_type_combinations: null,
35+
"joint_trajectory_controller::state_interface_type_combinations": null,
3636
}
3737
}
3838
allow_partial_joints_goal: {

0 commit comments

Comments
 (0)