Skip to content
Merged
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
12 changes: 9 additions & 3 deletions joint_trajectory_controller/test/test_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2675,8 +2675,10 @@ TEST_F(TrajectoryControllerTest, setting_scaling_factor_works_correctly)
rclcpp::executors::MultiThreadedExecutor executor;
std::vector<rclcpp::Parameter> params = {};
SetUpAndActivateTrajectoryController(executor, params);
// Create a QoS profile that matches the controller's speed_scaling subscriber
auto qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local();
auto speed_scaling_pub = node_->create_publisher<control_msgs::msg::SpeedScalingFactor>(
controller_name_ + "/speed_scaling_input", rclcpp::SystemDefaultsQoS());
controller_name_ + "/speed_scaling_input", qos);
subscribeToState(executor);

control_msgs::msg::SpeedScalingFactor msg;
Expand Down Expand Up @@ -2775,8 +2777,10 @@ TEST_F(TrajectoryControllerTest, scaling_state_interface_sets_value)
};
SetUpAndActivateTrajectoryController(executor, params);

// Create a QoS profile that matches the controller's speed_scaling subscriber
auto qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local();
auto speed_scaling_pub = node_->create_publisher<control_msgs::msg::SpeedScalingFactor>(
controller_name_ + "/speed_scaling_input", rclcpp::SystemDefaultsQoS());
controller_name_ + "/speed_scaling_input", qos);
subscribeToState(executor);
updateController();
// Spin to receive latest state
Expand Down Expand Up @@ -2810,8 +2814,10 @@ TEST_F(TrajectoryControllerTest, scaling_command_interface_sets_value)
};
SetUpAndActivateTrajectoryController(executor, params);

// Create a QoS profile that matches the controller's speed_scaling subscriber
auto qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local();
auto speed_scaling_pub = node_->create_publisher<control_msgs::msg::SpeedScalingFactor>(
controller_name_ + "/speed_scaling_input", rclcpp::SystemDefaultsQoS());
controller_name_ + "/speed_scaling_input", qos);
subscribeToState(executor);
updateController();
// Spin to receive latest state
Expand Down