@@ -82,6 +82,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_init()
82
82
controller_interface::InterfaceConfiguration
83
83
JointTrajectoryController::command_interface_configuration () const
84
84
{
85
+ const auto logger = get_node ()->get_logger ();
85
86
controller_interface::InterfaceConfiguration conf;
86
87
conf.type = controller_interface::interface_configuration_type::INDIVIDUAL;
87
88
if (dof_ == 0 )
@@ -101,12 +102,19 @@ JointTrajectoryController::command_interface_configuration() const
101
102
conf.names .push_back (joint_name + " /" + interface_type);
102
103
}
103
104
}
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
+ }
104
111
return conf;
105
112
}
106
113
107
114
controller_interface::InterfaceConfiguration
108
115
JointTrajectoryController::state_interface_configuration () const
109
116
{
117
+ const auto logger = get_node ()->get_logger ();
110
118
controller_interface::InterfaceConfiguration conf;
111
119
conf.type = controller_interface::interface_configuration_type::INDIVIDUAL;
112
120
conf.names .reserve (dof_ * params_.state_interfaces .size ());
@@ -117,33 +125,36 @@ JointTrajectoryController::state_interface_configuration() const
117
125
conf.names .push_back (joint_name + " /" + interface_type);
118
126
}
119
127
}
120
- if (params_.exchange_scaling_factor_with_hardware )
128
+ if (! params_.speed_scaling_state_interface_name . empty () )
121
129
{
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 );
123
134
}
124
135
return conf;
125
136
}
126
137
127
138
controller_interface::return_type JointTrajectoryController::update (
128
139
const rclcpp::Time & time, const rclcpp::Duration & period)
129
140
{
130
- if (params_.exchange_scaling_factor_with_hardware )
141
+ if (params_.speed_scaling_state_interface_name . empty () )
131
142
{
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 )
133
148
{
134
149
scaling_factor_ = state_interfaces_.back ().get_value ();
135
150
}
136
151
else
137
152
{
138
153
RCLCPP_ERROR (
139
154
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 ());
141
156
}
142
157
}
143
- else
144
- {
145
- scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT ());
146
- }
147
158
148
159
if (get_state ().id () == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
149
160
{
@@ -478,7 +489,8 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto
478
489
auto interface_has_values = [](const auto & joint_interface)
479
490
{
480
491
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)
482
494
{ return std::isnan (interface.get ().get_value ()); }) == joint_interface.end ();
483
495
};
484
496
@@ -548,7 +560,8 @@ bool JointTrajectoryController::read_commands_from_command_interfaces(
548
560
auto interface_has_values = [](const auto & joint_interface)
549
561
{
550
562
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)
552
565
{ return std::isnan (interface.get ().get_value ()); }) == joint_interface.end ();
553
566
};
554
567
@@ -919,6 +932,8 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
919
932
std::placeholders::_1, std::placeholders::_2));
920
933
921
934
// set scaling factor to low value default
935
+ RCLCPP_INFO (
936
+ logger, " Setting initial scaling factor to %2f" , params_.scaling_factor_initial_default );
922
937
scaling_factor_rt_buff_.writeFromNonRT (params_.scaling_factor_initial_default );
923
938
924
939
return CallbackReturn::SUCCESS;
0 commit comments