@@ -355,10 +355,10 @@ void IgnitionROS2ControlPlugin::Configure(
355
355
// setup actuators and mechanism control node.
356
356
// This call will block if ROS is not properly initialized.
357
357
std::string urdf_string;
358
- std::vector<hardware_interface::HardwareInfo> control_hardware ;
358
+ std::vector<hardware_interface::HardwareInfo> control_hardware_info ;
359
359
try {
360
360
urdf_string = this ->dataPtr ->getURDF ();
361
- control_hardware = hardware_interface::parse_control_resources_from_urdf (urdf_string);
361
+ control_hardware_info = hardware_interface::parse_control_resources_from_urdf (urdf_string);
362
362
} catch (const std::runtime_error & ex) {
363
363
RCLCPP_ERROR_STREAM (
364
364
this ->dataPtr ->node_ ->get_logger (),
@@ -381,15 +381,15 @@ void IgnitionROS2ControlPlugin::Configure(
381
381
return ;
382
382
}
383
383
384
- for (unsigned int i = 0 ; i < control_hardware .size (); ++i) {
385
- std::string robot_hw_sim_type_str_ = control_hardware [i].hardware_class_type ;
384
+ for (unsigned int i = 0 ; i < control_hardware_info .size (); ++i) {
385
+ std::string robot_hw_sim_type_str_ = control_hardware_info [i].hardware_class_type ;
386
386
auto ignitionSystem = std::unique_ptr<ign_ros2_control::IgnitionSystemInterface>(
387
387
this ->dataPtr ->robot_hw_sim_loader_ ->createUnmanagedInstance (robot_hw_sim_type_str_));
388
388
389
389
if (!ignitionSystem->initSim (
390
390
this ->dataPtr ->node_ ,
391
391
enabledJoints,
392
- control_hardware [i],
392
+ control_hardware_info [i],
393
393
_ecm,
394
394
this ->dataPtr ->update_rate ))
395
395
{
@@ -398,8 +398,14 @@ void IgnitionROS2ControlPlugin::Configure(
398
398
return ;
399
399
}
400
400
401
- resource_manager_->import_component (std::move (ignitionSystem), control_hardware[i]);
401
+ resource_manager_->import_component (std::move (ignitionSystem), control_hardware_info[i]);
402
+
403
+ rclcpp_lifecycle::State state (
404
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
405
+ hardware_interface::lifecycle_state_names::ACTIVE);
406
+ resource_manager_->set_component_state (control_hardware_info[i].name , state);
402
407
}
408
+
403
409
// Create the controller manager
404
410
RCLCPP_INFO (this ->dataPtr ->node_ ->get_logger (), " Loading controller_manager" );
405
411
this ->dataPtr ->controller_manager_ .reset (
0 commit comments