Skip to content

Commit d77582e

Browse files
Fix shadowed variables, redefinition and old-style casts (#2569)
1 parent cc3f43a commit d77582e

File tree

4 files changed

+4
-5
lines changed

4 files changed

+4
-5
lines changed

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@
5151
namespace controller_manager
5252
{
5353
class ParamListener;
54-
class Params;
54+
struct Params;
5555
using ControllersListIterator = std::vector<controller_manager::ControllerSpec>::const_iterator;
5656

5757
rclcpp::NodeOptions get_cm_node_options();

controller_manager/src/controller_manager.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1584,7 +1584,8 @@ controller_interface::return_type ControllerManager::switch_controller_cb(
15841584
}
15851585
}
15861586
RCLCPP_DEBUG(
1587-
get_logger(), "'%s' request vector has size %i", action.c_str(), (int)request_list.size());
1587+
get_logger(), "'%s' request vector has size %i", action.c_str(),
1588+
static_cast<int>(request_list.size()));
15881589

15891590
return result;
15901591
};
@@ -2557,7 +2558,7 @@ void ControllerManager::reload_controller_libraries_service_cb(
25572558
get_logger(),
25582559
"Controller manager: Cannot reload controller libraries because"
25592560
" there are still %i active controllers",
2560-
(int)active_controllers.size());
2561+
static_cast<int>(active_controllers.size()));
25612562
response->ok = false;
25622563
return;
25632564
}

controller_manager/test/test_chainable_controller/test_chainable_controller.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,6 @@ class TestChainableController : public controller_interface::ChainableController
8484
controller_interface::InterfaceConfiguration cmd_iface_cfg_;
8585
controller_interface::InterfaceConfiguration state_iface_cfg_;
8686
std::vector<std::string> reference_interface_names_;
87-
std::vector<std::string> exported_state_interface_names_;
8887
std::unique_ptr<semantic_components::IMUSensor> imu_sensor_;
8988

9089
realtime_tools::RealtimeBuffer<std::shared_ptr<CmdType>> rt_command_ptr_;

hardware_interface_testing/test/test_resource_manager_prepare_perform_switch.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -105,7 +105,6 @@ class ResourceManagerPreparePerformTest : public ResourceManagerTest
105105
std::unique_ptr<hardware_interface::LoanedStateInterface> claimed_actuator_position_state_;
106106

107107
// Scenarios defined by example criteria
108-
rclcpp::Node node_{"ResourceManagerPreparePerformTest"};
109108
std::vector<std::string> empty_keys = {};
110109
std::vector<std::string> non_existing_keys = {"elbow_joint/position", "should_joint/position"};
111110
std::vector<std::string> legal_keys_system = {"joint1/position", "joint2/position"};

0 commit comments

Comments
 (0)