@@ -187,6 +187,43 @@ controller_interface::CallbackReturn PidController::on_configure(
187
187
auto measured_state_callback =
188
188
[&](const std::shared_ptr<ControllerMeasuredStateMsg> state_msg) -> void
189
189
{
190
+ if (state_msg->dof_names .size () != reference_and_state_dof_names_.size ())
191
+ {
192
+ RCLCPP_ERROR (
193
+ get_node ()->get_logger (),
194
+ " Size of input data names (%zu) is not matching the expected size (%zu)." ,
195
+ state_msg->dof_names .size (), reference_and_state_dof_names_.size ());
196
+ return ;
197
+ }
198
+ if (state_msg->values .size () != reference_and_state_dof_names_.size ())
199
+ {
200
+ RCLCPP_ERROR (
201
+ get_node ()->get_logger (),
202
+ " Size of input data values (%zu) is not matching the expected size (%zu)." ,
203
+ state_msg->values .size (), reference_and_state_dof_names_.size ());
204
+ return ;
205
+ }
206
+
207
+ if (!state_msg->values_dot .empty ())
208
+ {
209
+ if (params_.reference_and_state_interfaces .size () != 2 )
210
+ {
211
+ RCLCPP_ERROR (
212
+ get_node ()->get_logger (),
213
+ " The reference_and_state_interfaces parameter has to have two interfaces [the "
214
+ " interface and the derivative of the interface], in order to use the values_dot "
215
+ " field." );
216
+ return ;
217
+ }
218
+ if (state_msg->values_dot .size () != reference_and_state_dof_names_.size ())
219
+ {
220
+ RCLCPP_ERROR (
221
+ get_node ()->get_logger (),
222
+ " Size of input data values_dot (%zu) is not matching the expected size (%zu)." ,
223
+ state_msg->values_dot .size (), reference_and_state_dof_names_.size ());
224
+ return ;
225
+ }
226
+ }
190
227
// TODO(destogl): Sort the input values based on joint and interface names
191
228
measured_state_.writeFromNonRT (state_msg);
192
229
};
@@ -363,6 +400,27 @@ std::vector<hardware_interface::CommandInterface> PidController::on_export_refer
363
400
return reference_interfaces;
364
401
}
365
402
403
+ std::vector<hardware_interface::StateInterface> PidController::on_export_state_interfaces ()
404
+ {
405
+ std::vector<hardware_interface::StateInterface> state_interfaces;
406
+ state_interfaces.reserve (state_interfaces_values_.size ());
407
+
408
+ state_interfaces_values_.resize (
409
+ reference_and_state_dof_names_.size () * params_.reference_and_state_interfaces .size (),
410
+ std::numeric_limits<double >::quiet_NaN ());
411
+ size_t index = 0 ;
412
+ for (const auto & interface : params_.reference_and_state_interfaces )
413
+ {
414
+ for (const auto & dof_name : reference_and_state_dof_names_)
415
+ {
416
+ state_interfaces.push_back (hardware_interface::StateInterface (
417
+ get_node ()->get_name (), dof_name + " /" + interface, &state_interfaces_values_[index ]));
418
+ ++index ;
419
+ }
420
+ }
421
+ return state_interfaces;
422
+ }
423
+
366
424
bool PidController::on_set_chained_mode (bool chained_mode)
367
425
{
368
426
// Always accept switch to/from chained mode
@@ -438,6 +496,12 @@ controller_interface::return_type PidController::update_and_write_commands(
438
496
}
439
497
}
440
498
499
+ // Fill the information of the exported state interfaces
500
+ for (size_t i = 0 ; i < measured_state_values_.size (); ++i)
501
+ {
502
+ state_interfaces_values_[i] = measured_state_values_[i];
503
+ }
504
+
441
505
for (size_t i = 0 ; i < dof_; ++i)
442
506
{
443
507
double tmp_command = std::numeric_limits<double >::quiet_NaN ();
0 commit comments