@@ -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}
@@ -58,7 +64,10 @@ controller_interface::InterfaceConfiguration ScaledJointTrajectoryController::st
5864{
5965 controller_interface::InterfaceConfiguration conf;
6066 conf = JointTrajectoryController::state_interface_configuration ();
61- conf.names .push_back (scaled_params_.speed_scaling_interface_name );
67+
68+ if (!scaled_params_.speed_scaling_interface_name .empty ()) {
69+ conf.names .push_back (scaled_params_.speed_scaling_interface_name );
70+ }
6271
6372 return conf;
6473}
@@ -70,17 +79,27 @@ controller_interface::CallbackReturn ScaledJointTrajectoryController::on_activat
7079 time_data.period = rclcpp::Duration::from_nanoseconds (0 );
7180 time_data.uptime = get_node ()->now ();
7281 time_data_.initRT (time_data);
82+
83+ // Set scaling interfaces
84+ if (!scaled_params_.speed_scaling_interface_name .empty ()) {
85+ auto it = std::find_if (state_interfaces_.begin (), state_interfaces_.end (), [&](auto & interface) {
86+ return (interface.get_name () == scaled_params_.speed_scaling_interface_name );
87+ });
88+ if (it != state_interfaces_.end ()) {
89+ scaling_state_interface_ = *it;
90+ } else {
91+ RCLCPP_ERROR (get_node ()->get_logger (), " Did not find speed scaling interface in state interfaces." );
92+ }
93+ }
94+
7395 return JointTrajectoryController::on_activate (state);
7496}
7597
7698controller_interface::return_type ScaledJointTrajectoryController::update (const rclcpp::Time& time,
7799 const rclcpp::Duration& period)
78100{
79- if (state_interfaces_.back ().get_name () == scaled_params_.speed_scaling_interface_name ) {
80- scaling_factor_ = state_interfaces_.back ().get_value ();
81- } else {
82- RCLCPP_ERROR (get_node ()->get_logger (), " Speed scaling interface (%s) not found in hardware interface." ,
83- scaled_params_.speed_scaling_interface_name .c_str ());
101+ if (scaling_state_interface_.has_value ()) {
102+ scaling_factor_ = scaling_state_interface_->get ().get_value ();
84103 }
85104
86105 if (get_state ().id () == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) {
0 commit comments