Skip to content

Commit 93b2d57

Browse files
ahcordeiche033
authored andcommitted
cherry-pick 48ba51a and resolve conflicts
Signed-off-by: Ian Chen <[email protected]>
1 parent a6f5044 commit 93b2d57

File tree

1 file changed

+12
-6
lines changed

1 file changed

+12
-6
lines changed

ign_ros2_control/src/ign_ros2_control_plugin.cpp

Lines changed: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -355,10 +355,10 @@ void IgnitionROS2ControlPlugin::Configure(
355355
// setup actuators and mechanism control node.
356356
// This call will block if ROS is not properly initialized.
357357
std::string urdf_string;
358-
std::vector<hardware_interface::HardwareInfo> control_hardware;
358+
std::vector<hardware_interface::HardwareInfo> control_hardware_info;
359359
try {
360360
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);
362362
} catch (const std::runtime_error & ex) {
363363
RCLCPP_ERROR_STREAM(
364364
this->dataPtr->node_->get_logger(),
@@ -381,15 +381,15 @@ void IgnitionROS2ControlPlugin::Configure(
381381
return;
382382
}
383383

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;
386386
auto ignitionSystem = std::unique_ptr<ign_ros2_control::IgnitionSystemInterface>(
387387
this->dataPtr->robot_hw_sim_loader_->createUnmanagedInstance(robot_hw_sim_type_str_));
388388

389389
if (!ignitionSystem->initSim(
390390
this->dataPtr->node_,
391391
enabledJoints,
392-
control_hardware[i],
392+
control_hardware_info[i],
393393
_ecm,
394394
this->dataPtr->update_rate))
395395
{
@@ -398,8 +398,14 @@ void IgnitionROS2ControlPlugin::Configure(
398398
return;
399399
}
400400

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);
402407
}
408+
403409
// Create the controller manager
404410
RCLCPP_INFO(this->dataPtr->node_->get_logger(), "Loading controller_manager");
405411
this->dataPtr->controller_manager_.reset(

0 commit comments

Comments
 (0)