diff --git a/ur_controllers/src/scaled_joint_trajectory_controller.cpp b/ur_controllers/src/scaled_joint_trajectory_controller.cpp index c28b07aae..bd0451510 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller.cpp +++ b/ur_controllers/src/scaled_joint_trajectory_controller.cpp @@ -67,8 +67,11 @@ controller_interface::InterfaceConfiguration ScaledJointTrajectoryController::st controller_interface::CallbackReturn ScaledJointTrajectoryController::on_activate(const rclcpp_lifecycle::State& state) { if (scaled_params_.use_speed_scaling_topic_instead) { + auto qos = rclcpp::QoS(10); + qos.transient_local(); + scaling_factor_sub_ = get_node()->create_subscription( - "~/speed_scaling_factor", 10, + scaled_params_.speed_scaling_topic_name, qos, [&](const ScalingFactorMsg& msg) { scaling_factor_ = std::clamp(msg.data / 100.0, 0.0, 1.0); }); } diff --git a/ur_controllers/src/scaled_joint_trajectory_controller_parameters.yaml b/ur_controllers/src/scaled_joint_trajectory_controller_parameters.yaml index 0c1c8cb35..0e7785bb4 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller_parameters.yaml +++ b/ur_controllers/src/scaled_joint_trajectory_controller_parameters.yaml @@ -7,5 +7,10 @@ scaled_joint_trajectory_controller: use_speed_scaling_topic_instead: { type: bool, default_value: false, - description: "Instead of using the speed_scaling_interface_name listen on ~/speed_scaling_factor" + description: "Instead of using the speed_scaling_interface_name listen on " + } + speed_scaling_topic_name: { + type: string, + default_value: "~/speed_scaling_factor", + description: "Topic name for the speed scaling factor (if enabled)" }