Skip to content

Commit 3fe6c37

Browse files
authored
Merge branch 'jazzy' into mergify/bp/jazzy/pr-2346
2 parents 4b275d6 + 9c9d361 commit 3fe6c37

24 files changed

+258
-117
lines changed

hardware_interface/include/hardware_interface/actuator.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,10 +51,16 @@ class Actuator final
5151

5252
Actuator & operator=(Actuator && other) = delete;
5353

54+
[[deprecated(
55+
"Replaced by const rclcpp_lifecycle::State & initialize(const "
56+
"hardware_interface::HardwareComponentParams & params).")]]
5457
const rclcpp_lifecycle::State & initialize(
5558
const HardwareInfo & actuator_info, rclcpp::Logger logger,
5659
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface);
5760

61+
[[deprecated(
62+
"Replaced by const rclcpp_lifecycle::State & initialize(const "
63+
"hardware_interface::HardwareComponentParams & params).")]]
5864
const rclcpp_lifecycle::State & initialize(
5965
const HardwareInfo & actuator_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock);
6066

hardware_interface/include/hardware_interface/actuator_interface.hpp

Lines changed: 12 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -140,6 +140,9 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
140140
* \returns CallbackReturn::SUCCESS if required data are provided and can be parsed.
141141
* \returns CallbackReturn::ERROR if any error happens or data are missing.
142142
*/
143+
[[deprecated(
144+
"Replaced by CallbackReturn init(const hardware_interface::HardwareComponentParams & "
145+
"params). Initialization is handled by the Framework.")]]
143146
CallbackReturn init(
144147
const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
145148
{
@@ -212,6 +215,7 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
212215
* \returns CallbackReturn::SUCCESS if required data are provided and can be parsed.
213216
* \returns CallbackReturn::ERROR if any error happens or data are missing.
214217
*/
218+
[[deprecated("Use on_init(const HardwareComponentInterfaceParams & params) instead.")]]
215219
virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
216220
{
217221
info_ = hardware_info;
@@ -233,7 +237,11 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
233237
virtual CallbackReturn on_init(
234238
const hardware_interface::HardwareComponentInterfaceParams & params)
235239
{
240+
// This is done for backward compatibility with the old on_init method.
241+
#pragma GCC diagnostic push
242+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
236243
return on_init(params.hardware_info);
244+
#pragma GCC diagnostic pop
237245
};
238246

239247
/// Exports all state interfaces for this hardware interface.
@@ -250,10 +258,8 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
250258
*/
251259
[[deprecated(
252260
"Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
253-
"Exporting is "
254-
"handled "
255-
"by the Framework.")]] virtual std::vector<StateInterface>
256-
export_state_interfaces()
261+
"Exporting is handled by the Framework.")]]
262+
virtual std::vector<StateInterface> export_state_interfaces()
257263
{
258264
// return empty vector by default. For backward compatibility we try calling
259265
// export_state_interfaces() and only when empty vector is returned call
@@ -327,10 +333,8 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
327333
*/
328334
[[deprecated(
329335
"Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
330-
"Exporting is "
331-
"handled "
332-
"by the Framework.")]] virtual std::vector<CommandInterface>
333-
export_command_interfaces()
336+
"Exporting is handled by the Framework.")]]
337+
virtual std::vector<CommandInterface> export_command_interfaces()
334338
{
335339
// return empty vector by default. For backward compatibility we try calling
336340
// export_command_interfaces() and only when empty vector is returned call

hardware_interface/include/hardware_interface/resource_manager.hpp

Lines changed: 17 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -134,8 +134,10 @@ class ResourceManager
134134
* \param[in] update_rate update rate of the main control loop, i.e., of the controller manager.
135135
* \returns false if URDF validation has failed.
136136
*/
137-
virtual bool load_and_initialize_components(
138-
const std::string & urdf, const unsigned int update_rate = 100);
137+
[[deprecated(
138+
"Use load_and_initialize_components(const ResourceManagerParams & params) "
139+
"instead")]] virtual bool
140+
load_and_initialize_components(const std::string & urdf, const unsigned int update_rate = 100);
139141

140142
/// Load resources from on a given URDF.
141143
/**
@@ -414,8 +416,10 @@ class ResourceManager
414416
* \param[in] actuator pointer to the actuator interface.
415417
* \param[in] hardware_info hardware info
416418
*/
417-
void import_component(
418-
std::unique_ptr<ActuatorInterface> actuator, const HardwareInfo & hardware_info);
419+
[[deprecated(
420+
"Use import_component(std::unique_ptr<ActuatorInterface> actuator, "
421+
"const HardwareComponentParams & params) instead")]] void
422+
import_component(std::unique_ptr<ActuatorInterface> actuator, const HardwareInfo & hardware_info);
419423

420424
/// Import a hardware component which is not listed in the URDF
421425
/**
@@ -430,8 +434,10 @@ class ResourceManager
430434
* \param[in] sensor pointer to the sensor interface.
431435
* \param[in] hardware_info hardware info
432436
*/
433-
void import_component(
434-
std::unique_ptr<SensorInterface> sensor, const HardwareInfo & hardware_info);
437+
[[deprecated(
438+
"Use import_component(std::unique_ptr<SensorInterface> sensor, "
439+
"const HardwareComponentParams & params) instead")]] void
440+
import_component(std::unique_ptr<SensorInterface> sensor, const HardwareInfo & hardware_info);
435441

436442
/// Import a hardware component which is not listed in the URDF
437443
/**
@@ -446,8 +452,10 @@ class ResourceManager
446452
* \param[in] system pointer to the system interface.
447453
* \param[in] hardware_info hardware info
448454
*/
449-
void import_component(
450-
std::unique_ptr<SystemInterface> system, const HardwareComponentParams & params);
455+
[[deprecated(
456+
"Use import_component(std::unique_ptr<SystemInterface> system, "
457+
"const HardwareComponentParams & params) instead")]] void
458+
import_component(std::unique_ptr<SystemInterface> system, const HardwareInfo & hardware_info);
451459

452460
/// Import a hardware component which is not listed in the URDF
453461
/**
@@ -498,7 +506,7 @@ class ResourceManager
498506
* and other parameters for the component.
499507
*/
500508
void import_component(
501-
std::unique_ptr<SystemInterface> system, const HardwareInfo & hardware_info);
509+
std::unique_ptr<SystemInterface> system, const HardwareComponentParams & params);
502510

503511
/// Return status for all components.
504512
/**

hardware_interface/include/hardware_interface/sensor.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,10 +51,16 @@ class Sensor final
5151

5252
Sensor & operator=(Sensor && other) = delete;
5353

54+
[[deprecated(
55+
"Replaced by const rclcpp_lifecycle::State & initialize(const "
56+
"hardware_interface::HardwareComponentParams & params).")]]
5457
const rclcpp_lifecycle::State & initialize(
5558
const HardwareInfo & sensor_info, rclcpp::Logger logger,
5659
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface);
5760

61+
[[deprecated(
62+
"Replaced by const rclcpp_lifecycle::State & initialize(const "
63+
"hardware_interface::HardwareComponentParams & params).")]]
5864
const rclcpp_lifecycle::State & initialize(
5965
const HardwareInfo & sensor_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock);
6066

hardware_interface/include/hardware_interface/sensor_interface.hpp

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -124,6 +124,9 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
124124
* \returns CallbackReturn::SUCCESS if required data are provided and can be parsed.
125125
* \returns CallbackReturn::ERROR if any error happens or data are missing.
126126
*/
127+
[[deprecated(
128+
"Replaced by CallbackReturn init(const hardware_interface::HardwareComponentParams & "
129+
"params). Initialization is handled by the Framework.")]]
127130
CallbackReturn init(
128131
const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
129132
{
@@ -175,6 +178,7 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
175178
* \returns CallbackReturn::SUCCESS if required data are provided and can be parsed.
176179
* \returns CallbackReturn::ERROR if any error happens or data are missing.
177180
*/
181+
[[deprecated("Use on_init(const HardwareComponentInterfaceParams & params) instead.")]]
178182
virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
179183
{
180184
info_ = hardware_info;
@@ -196,7 +200,11 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
196200
virtual CallbackReturn on_init(
197201
const hardware_interface::HardwareComponentInterfaceParams & params)
198202
{
203+
// This is done for backward compatibility with the old on_init method.
204+
#pragma GCC diagnostic push
205+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
199206
return on_init(params.hardware_info);
207+
#pragma GCC diagnostic pop
200208
};
201209

202210
/// Exports all state interfaces for this hardware interface.
@@ -213,9 +221,8 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
213221
*/
214222
[[deprecated(
215223
"Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
216-
"Exporting is handled "
217-
"by the Framework.")]] virtual std::vector<StateInterface>
218-
export_state_interfaces()
224+
"Exporting is handled by the Framework.")]]
225+
virtual std::vector<StateInterface> export_state_interfaces()
219226
{
220227
// return empty vector by default. For backward compatibility we try calling
221228
// export_state_interfaces() and only when empty vector is returned call

hardware_interface/include/hardware_interface/system.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,10 +51,16 @@ class System final
5151

5252
System & operator=(System && other) = delete;
5353

54+
[[deprecated(
55+
"Replaced by const rclcpp_lifecycle::State & initialize(const "
56+
"hardware_interface::HardwareComponentParams & params).")]]
5457
const rclcpp_lifecycle::State & initialize(
5558
const HardwareInfo & system_info, rclcpp::Logger logger,
5659
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface);
5760

61+
[[deprecated(
62+
"Replaced by const rclcpp_lifecycle::State & initialize(const "
63+
"hardware_interface::HardwareComponentParams & params).")]]
5864
const rclcpp_lifecycle::State & initialize(
5965
const HardwareInfo & system_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock);
6066

hardware_interface/include/hardware_interface/system_interface.hpp

Lines changed: 12 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -144,6 +144,9 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
144144
* \returns CallbackReturn::SUCCESS if required data are provided and can be parsed.
145145
* \returns CallbackReturn::ERROR if any error happens or data are missing.
146146
*/
147+
[[deprecated(
148+
"Replaced by CallbackReturn init(const hardware_interface::HardwareComponentParams & "
149+
"params). Initialization is handled by the Framework.")]]
147150
CallbackReturn init(
148151
const HardwareInfo & hardware_info, rclcpp::Logger logger, rclcpp::Clock::SharedPtr clock)
149152
{
@@ -216,6 +219,7 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
216219
* \returns CallbackReturn::SUCCESS if required data are provided and can be parsed.
217220
* \returns CallbackReturn::ERROR if any error happens or data are missing.
218221
*/
222+
[[deprecated("Use on_init(const HardwareComponentInterfaceParams & params) instead.")]]
219223
virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
220224
{
221225
info_ = hardware_info;
@@ -240,7 +244,11 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
240244
virtual CallbackReturn on_init(
241245
const hardware_interface::HardwareComponentInterfaceParams & params)
242246
{
247+
// This is done for backward compatibility with the old on_init method.
248+
#pragma GCC diagnostic push
249+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
243250
return on_init(params.hardware_info);
251+
#pragma GCC diagnostic pop
244252
};
245253

246254
/// Exports all state interfaces for this hardware interface.
@@ -257,9 +265,8 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
257265
*/
258266
[[deprecated(
259267
"Replaced by vector<StateInterface::ConstSharedPtr> on_export_state_interfaces() method. "
260-
"Exporting is handled "
261-
"by the Framework.")]] virtual std::vector<StateInterface>
262-
export_state_interfaces()
268+
"Exporting is handled by the Framework.")]]
269+
virtual std::vector<StateInterface> export_state_interfaces()
263270
{
264271
// return empty vector by default. For backward compatibility we try calling
265272
// export_state_interfaces() and only when empty vector is returned call
@@ -348,10 +355,8 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
348355
*/
349356
[[deprecated(
350357
"Replaced by vector<CommandInterface::SharedPtr> on_export_command_interfaces() method. "
351-
"Exporting is "
352-
"handled "
353-
"by the Framework.")]] virtual std::vector<CommandInterface>
354-
export_command_interfaces()
358+
"Exporting is handled by the Framework.")]]
359+
virtual std::vector<CommandInterface> export_command_interfaces()
355360
{
356361
// return empty vector by default. For backward compatibility we try calling
357362
// export_command_interfaces() and only when empty vector is returned call

hardware_interface/include/mock_components/generic_system.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,8 @@ static constexpr size_t ACCELERATION_INTERFACE_INDEX = 2;
4242
class GenericSystem : public hardware_interface::SystemInterface
4343
{
4444
public:
45-
CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override;
45+
CallbackReturn on_init(
46+
const hardware_interface::HardwareComponentInterfaceParams & params) override;
4647

4748
std::vector<hardware_interface::StateInterface> export_state_interfaces() override;
4849

hardware_interface/src/actuator.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,11 @@ const rclcpp_lifecycle::State & Actuator::initialize(
4949
const HardwareInfo & actuator_info, rclcpp::Logger logger,
5050
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
5151
{
52+
// This is done for backward compatibility with the old initialize method.
53+
#pragma GCC diagnostic push
54+
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
5255
return this->initialize(actuator_info, logger, clock_interface->get_clock());
56+
#pragma GCC diagnostic pop
5357
}
5458

5559
const rclcpp_lifecycle::State & Actuator::initialize(

hardware_interface/src/mock_components/generic_system.cpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -30,9 +30,10 @@
3030
namespace mock_components
3131
{
3232

33-
CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & info)
33+
CallbackReturn GenericSystem::on_init(
34+
const hardware_interface::HardwareComponentInterfaceParams & params)
3435
{
35-
if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS)
36+
if (hardware_interface::SystemInterface::on_init(params) != CallbackReturn::SUCCESS)
3637
{
3738
return CallbackReturn::ERROR;
3839
}
@@ -83,7 +84,7 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i
8384
// check if there is parameter that disables commands
8485
// this way we simulate disconnected driver
8586
it = get_hardware_info().hardware_parameters.find("disable_commands");
86-
if (it != info.hardware_parameters.end())
87+
if (it != get_hardware_info().hardware_parameters.end())
8788
{
8889
command_propagation_disabled_ = hardware_interface::parse_bool(it->second);
8990
}
@@ -94,7 +95,7 @@ CallbackReturn GenericSystem::on_init(const hardware_interface::HardwareInfo & i
9495

9596
// check if there is parameter that enables dynamic calculation
9697
it = get_hardware_info().hardware_parameters.find("calculate_dynamics");
97-
if (it != info.hardware_parameters.end())
98+
if (it != get_hardware_info().hardware_parameters.end())
9899
{
99100
calculate_dynamics_ = hardware_interface::parse_bool(it->second);
100101
}

0 commit comments

Comments
 (0)