@@ -220,14 +220,6 @@ class ResourceStorage
220
220
return is_loaded;
221
221
}
222
222
223
- template <class HardwareT >
224
- bool initialize_hardware (const HardwareInfo & hardware_info, HardwareT & hardware)
225
- {
226
- hardware_interface::HardwareComponentParams params;
227
- params.hardware_info = hardware_info;
228
- return initialize_hardware (params, hardware);
229
- }
230
-
231
223
template <class HardwareT >
232
224
bool initialize_hardware (
233
225
const hardware_interface::HardwareComponentParams & params, HardwareT & hardware)
@@ -1101,28 +1093,6 @@ class ResourceStorage
1101
1093
}
1102
1094
}
1103
1095
1104
- // TODO(destogl): Propagate "false" up, if happens in initialize_hardware
1105
- bool load_and_initialize_actuator (const HardwareInfo & hardware_info)
1106
- {
1107
- hardware_interface::HardwareComponentParams params;
1108
- params.hardware_info = hardware_info;
1109
- return load_and_initialize_actuator (params);
1110
- }
1111
-
1112
- bool load_and_initialize_sensor (const HardwareInfo & hardware_info)
1113
- {
1114
- hardware_interface::HardwareComponentParams params;
1115
- params.hardware_info = hardware_info;
1116
- return load_and_initialize_sensor (params);
1117
- }
1118
-
1119
- bool load_and_initialize_system (const HardwareInfo & hardware_info)
1120
- {
1121
- hardware_interface::HardwareComponentParams params;
1122
- params.hardware_info = hardware_info;
1123
- return load_and_initialize_system (params);
1124
- }
1125
-
1126
1096
bool load_and_initialize_actuator (const hardware_interface::HardwareComponentParams & params)
1127
1097
{
1128
1098
auto load_and_init_actuators = [&](auto & container)
@@ -1199,29 +1169,6 @@ class ResourceStorage
1199
1169
return load_and_init_systems (systems_);
1200
1170
}
1201
1171
1202
- void initialize_actuator (
1203
- std::unique_ptr<ActuatorInterface> actuator, const HardwareInfo & hardware_info)
1204
- {
1205
- hardware_interface::HardwareComponentParams params;
1206
- params.hardware_info = hardware_info;
1207
- return initialize_actuator (std::move (actuator), params);
1208
- }
1209
- void initialize_sensor (
1210
- std::unique_ptr<SensorInterface> sensor, const HardwareInfo & hardware_info)
1211
- {
1212
- hardware_interface::HardwareComponentParams params;
1213
- params.hardware_info = hardware_info;
1214
- return initialize_sensor (std::move (sensor), params);
1215
- }
1216
-
1217
- void initialize_system (
1218
- std::unique_ptr<SystemInterface> system, const HardwareInfo & hardware_info)
1219
- {
1220
- hardware_interface::HardwareComponentParams params;
1221
- params.hardware_info = hardware_info;
1222
- return initialize_system (std::move (system), params);
1223
- }
1224
-
1225
1172
void initialize_actuator (
1226
1173
std::unique_ptr<ActuatorInterface> actuator,
1227
1174
const hardware_interface::HardwareComponentParams & params)
0 commit comments