@@ -82,6 +82,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_init()
8282controller_interface::InterfaceConfiguration
8383JointTrajectoryController::command_interface_configuration () const
8484{
85+ const auto logger = get_node ()->get_logger ();
8586 controller_interface::InterfaceConfiguration conf;
8687 conf.type = controller_interface::interface_configuration_type::INDIVIDUAL;
8788 if (dof_ == 0 )
@@ -101,12 +102,19 @@ JointTrajectoryController::command_interface_configuration() const
101102 conf.names .push_back (joint_name + " /" + interface_type);
102103 }
103104 }
105+ if (!params_.speed_scaling_command_interface_name .empty ())
106+ {
107+ RCLCPP_WARN (
108+ logger, " Using a command interface for setting the scaling factor isn't supported, yet." );
109+ conf.names .push_back (params_.speed_scaling_command_interface_name );
110+ }
104111 return conf;
105112}
106113
107114controller_interface::InterfaceConfiguration
108115JointTrajectoryController::state_interface_configuration () const
109116{
117+ const auto logger = get_node ()->get_logger ();
110118 controller_interface::InterfaceConfiguration conf;
111119 conf.type = controller_interface::interface_configuration_type::INDIVIDUAL;
112120 conf.names .reserve (dof_ * params_.state_interfaces .size ());
@@ -117,33 +125,36 @@ JointTrajectoryController::state_interface_configuration() const
117125 conf.names .push_back (joint_name + " /" + interface_type);
118126 }
119127 }
120- if (params_.exchange_scaling_factor_with_hardware )
128+ if (! params_.speed_scaling_state_interface_name . empty () )
121129 {
122- conf.names .push_back (params_.speed_scaling_interface_name );
130+ RCLCPP_INFO (
131+ logger, " Using scaling state from the hardware from interface %s." ,
132+ params_.speed_scaling_state_interface_name .c_str ());
133+ conf.names .push_back (params_.speed_scaling_state_interface_name );
123134 }
124135 return conf;
125136}
126137
127138controller_interface::return_type JointTrajectoryController::update (
128139 const rclcpp::Time & time, const rclcpp::Duration & period)
129140{
130- if (params_.exchange_scaling_factor_with_hardware )
141+ if (params_.speed_scaling_state_interface_name . empty () )
131142 {
132- if (state_interfaces_.back ().get_name () == params_.speed_scaling_interface_name )
143+ scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT ());
144+ }
145+ else
146+ {
147+ if (state_interfaces_.back ().get_name () == params_.speed_scaling_state_interface_name )
133148 {
134149 scaling_factor_ = state_interfaces_.back ().get_value ();
135150 }
136151 else
137152 {
138153 RCLCPP_ERROR (
139154 get_node ()->get_logger (), " Speed scaling interface (%s) not found in hardware interface." ,
140- params_.speed_scaling_interface_name .c_str ());
155+ params_.speed_scaling_state_interface_name .c_str ());
141156 }
142157 }
143- else
144- {
145- scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT ());
146- }
147158
148159 if (get_state ().id () == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
149160 {
@@ -478,7 +489,8 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto
478489 auto interface_has_values = [](const auto & joint_interface)
479490 {
480491 return std::find_if (
481- joint_interface.begin (), joint_interface.end (), [](const auto & interface)
492+ joint_interface.begin (), joint_interface.end (),
493+ [](const auto & interface)
482494 { return std::isnan (interface.get ().get_value ()); }) == joint_interface.end ();
483495 };
484496
@@ -548,7 +560,8 @@ bool JointTrajectoryController::read_commands_from_command_interfaces(
548560 auto interface_has_values = [](const auto & joint_interface)
549561 {
550562 return std::find_if (
551- joint_interface.begin (), joint_interface.end (), [](const auto & interface)
563+ joint_interface.begin (), joint_interface.end (),
564+ [](const auto & interface)
552565 { return std::isnan (interface.get ().get_value ()); }) == joint_interface.end ();
553566 };
554567
@@ -919,6 +932,8 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
919932 std::placeholders::_1, std::placeholders::_2));
920933
921934 // set scaling factor to low value default
935+ RCLCPP_INFO (
936+ logger, " Setting initial scaling factor to %2f" , params_.scaling_factor_initial_default );
922937 scaling_factor_rt_buff_.writeFromNonRT (params_.scaling_factor_initial_default );
923938
924939 return CallbackReturn::SUCCESS;
0 commit comments