Skip to content

Commit

Permalink
Move logging to function that's only called once
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch committed Oct 14, 2024
1 parent 8a1dd35 commit fd546b5
Showing 1 changed file with 6 additions and 4 deletions.
10 changes: 6 additions & 4 deletions ur_controllers/src/scaled_joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,12 @@ controller_interface::CallbackReturn ScaledJointTrajectoryController::on_init()
// Create the parameter listener and get the parameters
scaled_param_listener_ = std::make_shared<scaled_joint_trajectory_controller::ParamListener>(get_node());
scaled_params_ = scaled_param_listener_->get_params();
if (!scaled_params_.speed_scaling_interface_name.empty()) {
RCLCPP_INFO(get_node()->get_logger(), "Using scaling state from the hardware from interface %s.",
scaled_params_.speed_scaling_interface_name.c_str());
} else {
RCLCPP_INFO(get_node()->get_logger(), "No scaling interface set. This controller will not use speed scaling.");
}

return JointTrajectoryController::on_init();
}
Expand All @@ -60,11 +66,7 @@ controller_interface::InterfaceConfiguration ScaledJointTrajectoryController::st
conf = JointTrajectoryController::state_interface_configuration();

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

return conf;
Expand Down

0 comments on commit fd546b5

Please sign in to comment.