Skip to content

Commit 2d250a2

Browse files
author
Lennart Nachtigall
committed
Allow changing topic name, made topic transient_local
1 parent 61baffb commit 2d250a2

File tree

2 files changed

+10
-2
lines changed

2 files changed

+10
-2
lines changed

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,8 +67,11 @@ controller_interface::InterfaceConfiguration ScaledJointTrajectoryController::st
6767
controller_interface::CallbackReturn ScaledJointTrajectoryController::on_activate(const rclcpp_lifecycle::State& state)
6868
{
6969
if (scaled_params_.use_speed_scaling_topic_instead) {
70+
auto qos = rclcpp::QoS(10);
71+
qos.transient_local();
72+
7073
scaling_factor_sub_ = get_node()->create_subscription<ScalingFactorMsg>(
71-
"~/speed_scaling_factor", 10,
74+
scaled_params_.speed_scaling_topic_name, qos,
7275
[&](const ScalingFactorMsg& msg) { scaling_factor_ = std::clamp(msg.data / 100.0, 0.0, 1.0); });
7376
}
7477

ur_controllers/src/scaled_joint_trajectory_controller_parameters.yaml

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,5 +7,10 @@ scaled_joint_trajectory_controller:
77
use_speed_scaling_topic_instead: {
88
type: bool,
99
default_value: false,
10-
description: "Instead of using the speed_scaling_interface_name listen on ~/speed_scaling_factor"
10+
description: "Instead of using the speed_scaling_interface_name listen on <speed_scaling_topic_name>"
11+
}
12+
speed_scaling_topic_name: {
13+
type: string,
14+
default_value: "~/speed_scaling_factor",
15+
description: "Topic name for the speed scaling factor (if enabled)"
1116
}

0 commit comments

Comments
 (0)