Skip to content

Commit fd546b5

Browse files
author
Felix Exner
committed
Move logging to function that's only called once
1 parent 8a1dd35 commit fd546b5

File tree

1 file changed

+6
-4
lines changed

1 file changed

+6
-4
lines changed

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,12 @@ controller_interface::CallbackReturn ScaledJointTrajectoryController::on_init()
5050
// Create the parameter listener and get the parameters
5151
scaled_param_listener_ = std::make_shared<scaled_joint_trajectory_controller::ParamListener>(get_node());
5252
scaled_params_ = scaled_param_listener_->get_params();
53+
if (!scaled_params_.speed_scaling_interface_name.empty()) {
54+
RCLCPP_INFO(get_node()->get_logger(), "Using scaling state from the hardware from interface %s.",
55+
scaled_params_.speed_scaling_interface_name.c_str());
56+
} else {
57+
RCLCPP_INFO(get_node()->get_logger(), "No scaling interface set. This controller will not use speed scaling.");
58+
}
5359

5460
return JointTrajectoryController::on_init();
5561
}
@@ -60,11 +66,7 @@ controller_interface::InterfaceConfiguration ScaledJointTrajectoryController::st
6066
conf = JointTrajectoryController::state_interface_configuration();
6167

6268
if (!scaled_params_.speed_scaling_interface_name.empty()) {
63-
RCLCPP_INFO(get_node()->get_logger(), "Using scaling state from the hardware from interface %s.",
64-
scaled_params_.speed_scaling_interface_name.c_str());
6569
conf.names.push_back(scaled_params_.speed_scaling_interface_name);
66-
} else {
67-
RCLCPP_INFO(get_node()->get_logger(), "No scaling interface set. This controller will not use speed scaling.");
6870
}
6971

7072
return conf;

0 commit comments

Comments
 (0)