Skip to content

Commit e0fff8d

Browse files
committed
fix parameter loading in tests
1 parent 38e0ff3 commit e0fff8d

File tree

2 files changed

+14
-14
lines changed

2 files changed

+14
-14
lines changed

joint_trajectory_controller/test/test_trajectory_actions.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1115,7 +1115,7 @@ TEST_P(TestTrajectoryActionsTestScalingFactor, test_scaling_execution_time_succe
11151115
// the error will be whatever the command diff is.
11161116
std::vector<rclcpp::Parameter> params = {
11171117
rclcpp::Parameter("open_loop_control", false),
1118-
rclcpp::Parameter("scaling_factor_initial_default", scaling_factor),
1118+
rclcpp::Parameter("speed_scaling.initial_scaling_factor", scaling_factor),
11191119
rclcpp::Parameter("constraints.joint1.trajectory", state_tol),
11201120
rclcpp::Parameter("constraints.joint2.trajectory", state_tol),
11211121
rclcpp::Parameter("constraints.joint3.trajectory", state_tol),
@@ -1192,7 +1192,7 @@ TEST_P(TestTrajectoryActionsTestScalingFactor, test_scaling_sampling_is_correct)
11921192
{
11931193
double scaling_factor = GetParam();
11941194
std::vector<rclcpp::Parameter> params = {
1195-
rclcpp::Parameter("scaling_factor_initial_default", scaling_factor),
1195+
rclcpp::Parameter("speed_scaling.initial_scaling_factor", scaling_factor),
11961196
rclcpp::Parameter("constraints.joint1.goal", 1e-3),
11971197
rclcpp::Parameter("constraints.joint2.goal", 1e-3),
11981198
rclcpp::Parameter("constraints.joint3.goal", 1e-3),

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -2697,7 +2697,7 @@ TEST_F(TrajectoryControllerTest, scaling_factor_from_param)
26972697
double initial_factor = 0.123;
26982698
rclcpp::executors::MultiThreadedExecutor executor;
26992699
std::vector<rclcpp::Parameter> params = {
2700-
rclcpp::Parameter("speed_scaling/initial_scaling_factor", initial_factor),
2700+
rclcpp::Parameter("speed_scaling.initial_scaling_factor", initial_factor),
27012701
};
27022702
SetUpAndActivateTrajectoryController(executor, params);
27032703
subscribeToState(executor);
@@ -2714,8 +2714,8 @@ TEST_F(
27142714
double initial_factor = 0.123;
27152715
rclcpp::executors::MultiThreadedExecutor executor;
27162716
std::vector<rclcpp::Parameter> params = {
2717-
rclcpp::Parameter("speed_scaling/initial_scaling_factor", initial_factor),
2718-
rclcpp::Parameter("speed_scaling/state_interface", "idontexist"),
2717+
rclcpp::Parameter("speed_scaling.initial_scaling_factor", initial_factor),
2718+
rclcpp::Parameter("speed_scaling.state_interface", "idontexist"),
27192719
};
27202720
SetUpTrajectoryController(executor, params);
27212721

@@ -2732,8 +2732,8 @@ TEST_F(
27322732
double initial_factor = 0.123;
27332733
rclcpp::executors::MultiThreadedExecutor executor;
27342734
std::vector<rclcpp::Parameter> params = {
2735-
rclcpp::Parameter("speed_scaling/initial_scaling_factor", initial_factor),
2736-
rclcpp::Parameter("speed_scaling/command_interface", "idontexist"),
2735+
rclcpp::Parameter("speed_scaling.initial_scaling_factor", initial_factor),
2736+
rclcpp::Parameter("speed_scaling.command_interface", "idontexist"),
27372737
};
27382738
SetUpTrajectoryController(executor, params);
27392739

@@ -2749,8 +2749,8 @@ TEST_F(TrajectoryControllerTest, scaling_state_interface_sets_value)
27492749
double initial_factor = 0.123;
27502750
rclcpp::executors::MultiThreadedExecutor executor;
27512751
std::vector<rclcpp::Parameter> params = {
2752-
rclcpp::Parameter("speed_scaling/initial_scaling_factor", initial_factor),
2753-
rclcpp::Parameter("speed_scaling/state_interface", "speed_scaling/speed_scaling_factor"),
2752+
rclcpp::Parameter("speed_scaling.initial_scaling_factor", initial_factor),
2753+
rclcpp::Parameter("speed_scaling.state_interface", "speed_scaling/speed_scaling_factor"),
27542754
};
27552755
SetUpAndActivateTrajectoryController(executor, params);
27562756

@@ -2783,9 +2783,9 @@ TEST_F(TrajectoryControllerTest, scaling_command_interface_sets_value)
27832783
double initial_factor = 0.123;
27842784
rclcpp::executors::MultiThreadedExecutor executor;
27852785
std::vector<rclcpp::Parameter> params = {
2786-
rclcpp::Parameter("speed_scaling/initial_scaling_factor", initial_factor),
2787-
rclcpp::Parameter("speed_scaling/state_interface", "speed_scaling/speed_scaling_factor"),
2788-
rclcpp::Parameter("speed_scaling/command_interface", "speed_scaling/target_speed_fraction_cmd"),
2786+
rclcpp::Parameter("speed_scaling.initial_scaling_factor", initial_factor),
2787+
rclcpp::Parameter("speed_scaling.state_interface", "speed_scaling/speed_scaling_factor"),
2788+
rclcpp::Parameter("speed_scaling.command_interface", "speed_scaling/target_speed_fraction_cmd"),
27892789
};
27902790
SetUpAndActivateTrajectoryController(executor, params);
27912791

@@ -2818,8 +2818,8 @@ TEST_F(TrajectoryControllerTest, activate_with_scaling_interfaces)
28182818
{
28192819
rclcpp::executors::MultiThreadedExecutor executor;
28202820
std::vector<rclcpp::Parameter> params = {
2821-
rclcpp::Parameter("speed_scaling/state_interface", "speed_scaling/speed_scaling_factor"),
2822-
rclcpp::Parameter("speed_scaling/command_interface", "speed_scaling/target_speed_fraction_cmd"),
2821+
rclcpp::Parameter("speed_scaling.state_interface", "speed_scaling/speed_scaling_factor"),
2822+
rclcpp::Parameter("speed_scaling.command_interface", "speed_scaling/target_speed_fraction_cmd"),
28232823
};
28242824
SetUpTrajectoryController(executor, params);
28252825

0 commit comments

Comments
 (0)