Skip to content

Commit cd7e522

Browse files
authored
Cleanup old internal API (#2346)
1 parent db1edb0 commit cd7e522

File tree

2 files changed

+1
-53
lines changed

2 files changed

+1
-53
lines changed

controller_manager/src/controller_manager.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -626,6 +626,7 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript
626626
params.clock = trigger_clock_;
627627
params.logger = this->get_logger();
628628
params.executor = executor_;
629+
params.update_rate = static_cast<unsigned int>(params_->update_rate);
629630
if (!resource_manager_->load_and_initialize_components(params))
630631
{
631632
RCLCPP_WARN(

hardware_interface/src/resource_manager.cpp

Lines changed: 0 additions & 53 deletions
Original file line numberDiff line numberDiff line change
@@ -234,14 +234,6 @@ class ResourceStorage
234234
return is_loaded;
235235
}
236236

237-
template <class HardwareT>
238-
bool initialize_hardware(const HardwareInfo & hardware_info, HardwareT & hardware)
239-
{
240-
hardware_interface::HardwareComponentParams params;
241-
params.hardware_info = hardware_info;
242-
return initialize_hardware(params, hardware);
243-
}
244-
245237
template <class HardwareT>
246238
bool initialize_hardware(
247239
const hardware_interface::HardwareComponentParams & params, HardwareT & hardware)
@@ -1115,28 +1107,6 @@ class ResourceStorage
11151107
}
11161108
}
11171109

1118-
// TODO(destogl): Propagate "false" up, if happens in initialize_hardware
1119-
bool load_and_initialize_actuator(const HardwareInfo & hardware_info)
1120-
{
1121-
hardware_interface::HardwareComponentParams params;
1122-
params.hardware_info = hardware_info;
1123-
return load_and_initialize_actuator(params);
1124-
}
1125-
1126-
bool load_and_initialize_sensor(const HardwareInfo & hardware_info)
1127-
{
1128-
hardware_interface::HardwareComponentParams params;
1129-
params.hardware_info = hardware_info;
1130-
return load_and_initialize_sensor(params);
1131-
}
1132-
1133-
bool load_and_initialize_system(const HardwareInfo & hardware_info)
1134-
{
1135-
hardware_interface::HardwareComponentParams params;
1136-
params.hardware_info = hardware_info;
1137-
return load_and_initialize_system(params);
1138-
}
1139-
11401110
bool load_and_initialize_actuator(const hardware_interface::HardwareComponentParams & params)
11411111
{
11421112
auto load_and_init_actuators = [&](auto & container)
@@ -1213,29 +1183,6 @@ class ResourceStorage
12131183
return load_and_init_systems(systems_);
12141184
}
12151185

1216-
void initialize_actuator(
1217-
std::unique_ptr<ActuatorInterface> actuator, const HardwareInfo & hardware_info)
1218-
{
1219-
hardware_interface::HardwareComponentParams params;
1220-
params.hardware_info = hardware_info;
1221-
return initialize_actuator(std::move(actuator), params);
1222-
}
1223-
void initialize_sensor(
1224-
std::unique_ptr<SensorInterface> sensor, const HardwareInfo & hardware_info)
1225-
{
1226-
hardware_interface::HardwareComponentParams params;
1227-
params.hardware_info = hardware_info;
1228-
return initialize_sensor(std::move(sensor), params);
1229-
}
1230-
1231-
void initialize_system(
1232-
std::unique_ptr<SystemInterface> system, const HardwareInfo & hardware_info)
1233-
{
1234-
hardware_interface::HardwareComponentParams params;
1235-
params.hardware_info = hardware_info;
1236-
return initialize_system(std::move(system), params);
1237-
}
1238-
12391186
void initialize_actuator(
12401187
std::unique_ptr<ActuatorInterface> actuator,
12411188
const hardware_interface::HardwareComponentParams & params)

0 commit comments

Comments
 (0)