Skip to content

Commit 32b08ab

Browse files
committed
Modified unused parameters adding maybe_unused
Signed-off-by: Wonho Yun <[email protected]>
1 parent 99e1702 commit 32b08ab

File tree

1 file changed

+5
-5
lines changed

1 file changed

+5
-5
lines changed

src/dynamixel_hardware_interface.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -376,13 +376,13 @@ DynamixelHardware::export_command_interfaces()
376376
}
377377

378378
hardware_interface::CallbackReturn DynamixelHardware::on_activate(
379-
const rclcpp_lifecycle::State & previous_state)
379+
[[maybe_unused]] const rclcpp_lifecycle::State & previous_state)
380380
{
381381
return start();
382382
}
383383

384384
hardware_interface::CallbackReturn DynamixelHardware::on_deactivate(
385-
const rclcpp_lifecycle::State & previous_state)
385+
[[maybe_unused]] const rclcpp_lifecycle::State & previous_state)
386386
{
387387
return stop();
388388
}
@@ -440,7 +440,7 @@ hardware_interface::CallbackReturn DynamixelHardware::stop()
440440
}
441441

442442
hardware_interface::return_type DynamixelHardware::read(
443-
const rclcpp::Time & time, const rclcpp::Duration & period)
443+
[[maybe_unused]] const rclcpp::Time & time, const rclcpp::Duration & period)
444444
{
445445
double period_ms = period.seconds() * 1000;
446446
if (dxl_status_ == REBOOTING) {
@@ -503,7 +503,7 @@ hardware_interface::return_type DynamixelHardware::read(
503503
return hardware_interface::return_type::OK;
504504
}
505505
hardware_interface::return_type DynamixelHardware::write(
506-
const rclcpp::Time & time, const rclcpp::Duration & period)
506+
[[maybe_unused]] const rclcpp::Time & time, const rclcpp::Duration & period)
507507
{
508508
if (dxl_status_ == DXL_OK || dxl_status_ == HW_ERROR) {
509509
dxl_comm_->WriteItemBuf();
@@ -1051,7 +1051,7 @@ void DynamixelHardware::set_dxl_data_srv_callback(
10511051
}
10521052

10531053
void DynamixelHardware::reboot_dxl_srv_callback(
1054-
const std::shared_ptr<dynamixel_interfaces::srv::RebootDxl::Request> request,
1054+
[[maybe_unused]] const std::shared_ptr<dynamixel_interfaces::srv::RebootDxl::Request> request,
10551055
std::shared_ptr<dynamixel_interfaces::srv::RebootDxl::Response> response)
10561056
{
10571057
if (CommReset()) {

0 commit comments

Comments
 (0)