Skip to content

Commit

Permalink
Allow changing topic name, made topic transient_local
Browse files Browse the repository at this point in the history
  • Loading branch information
Lennart Nachtigall committed Nov 9, 2023
1 parent 61baffb commit 2d250a2
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 2 deletions.
5 changes: 4 additions & 1 deletion ur_controllers/src/scaled_joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<ScalingFactorMsg>(
"~/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); });
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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>"
}
speed_scaling_topic_name: {
type: string,
default_value: "~/speed_scaling_factor",
description: "Topic name for the speed scaling factor (if enabled)"
}

0 comments on commit 2d250a2

Please sign in to comment.