Skip to content

Commit

Permalink
Unused header cleanup (#1627)
Browse files Browse the repository at this point in the history
  • Loading branch information
henrygerardmoore authored Jul 21, 2024
1 parent b7bbdd6 commit 6631270
Show file tree
Hide file tree
Showing 84 changed files with 40 additions and 598 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#define CONTROLLER_INTERFACE__CONTROLLER_INTERFACE_HPP_

#include <memory>
#include <string>
#include <vector>

#include "controller_interface/controller_interface_base.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/version.h"
#include "rclcpp_lifecycle/lifecycle_node.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#ifndef SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_
#define SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_

#include <limits>
#include <string>
#include <vector>

Expand Down
6 changes: 0 additions & 6 deletions controller_interface/src/controller_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,8 @@

#include "controller_interface/controller_interface.hpp"

#include <memory>
#include <string>
#include <utility>
#include <vector>

#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"

namespace controller_interface
{
ControllerInterface::ControllerInterface() : ControllerInterfaceBase() {}
Expand Down
1 change: 0 additions & 1 deletion controller_interface/src/controller_interface_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#include <utility>
#include <vector>

#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"

namespace controller_interface
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,13 @@
#ifndef TEST_CHAINABLE_CONTROLLER_INTERFACE_HPP_
#define TEST_CHAINABLE_CONTROLLER_INTERFACE_HPP_

#include <gmock/gmock.h>

#include <string>
#include <vector>

#include "gmock/gmock.h"

#include "controller_interface/chainable_controller_interface.hpp"
#include "hardware_interface/handle.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

constexpr char TEST_CONTROLLER_NAME[] = "testable_chainable_controller";
constexpr double INTERFACE_VALUE = 1989.0;
Expand Down
1 change: 0 additions & 1 deletion controller_interface/test/test_controller_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#define TEST_CONTROLLER_INTERFACE_HPP_

#include "controller_interface/controller_interface.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"

constexpr char TEST_CONTROLLER_NAME[] = "testable_controller_interface";

Expand Down
1 change: 0 additions & 1 deletion controller_interface/test/test_controller_with_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#include <gtest/gtest.h>
#include <string>
#include "ament_index_cpp/get_package_prefix.hpp"
#include "rclcpp/rclcpp.hpp"

class FriendControllerWithOptions : public controller_with_options::ControllerWithOptions
{
Expand Down
2 changes: 0 additions & 2 deletions controller_interface/test/test_controller_with_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,9 @@
#define TEST_CONTROLLER_WITH_OPTIONS_HPP_

#include <map>
#include <memory>
#include <string>

#include "controller_interface/controller_interface.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"

namespace controller_with_options
{
Expand Down
4 changes: 2 additions & 2 deletions controller_interface/test/test_force_torque_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,12 @@
#ifndef TEST_FORCE_TORQUE_SENSOR_HPP_
#define TEST_FORCE_TORQUE_SENSOR_HPP_

#include <gmock/gmock.h>

#include <memory>
#include <string>
#include <vector>

#include "gmock/gmock.h"

#include "semantic_components/force_torque_sensor.hpp"

// implementing and friending so we can access member variables
Expand Down
4 changes: 2 additions & 2 deletions controller_interface/test/test_imu_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,12 @@
#ifndef TEST_IMU_SENSOR_HPP_
#define TEST_IMU_SENSOR_HPP_

#include <gmock/gmock.h>

#include <memory>
#include <string>
#include <vector>

#include "gmock/gmock.h"

#include "semantic_components/imu_sensor.hpp"

// implementing and friending so we can access member variables
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,12 @@
#ifndef TEST_SEMANTIC_COMPONENT_INTERFACE_HPP_
#define TEST_SEMANTIC_COMPONENT_INTERFACE_HPP_

#include <gmock/gmock.h>

#include <memory>
#include <string>

#include "geometry_msgs/msg/wrench.hpp"
#include "gmock/gmock.h"
#include "semantic_components/semantic_component_interface.hpp"

// implementing and friending so we can access member variables
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include <map>
#include <memory>
#include <string>
#include <tuple>
#include <unordered_map>
#include <utility>
#include <vector>
Expand All @@ -42,17 +41,12 @@
#include "controller_manager_msgs/srv/unload_controller.hpp"

#include "diagnostic_updater/diagnostic_updater.hpp"
#include "hardware_interface/handle.hpp"
#include "hardware_interface/resource_manager.hpp"

#include "pluginlib/class_loader.hpp"

#include "rclcpp/executor.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

namespace controller_manager
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,10 @@
#ifndef CONTROLLER_MANAGER__CONTROLLER_SPEC_HPP_
#define CONTROLLER_MANAGER__CONTROLLER_SPEC_HPP_

#include <map>
#include <memory>
#include <string>
#include <vector>
#include "controller_interface/controller_interface.hpp"
#include "controller_interface/controller_interface_base.hpp"
#include "hardware_interface/controller_info.hpp"

namespace controller_manager
Expand Down
2 changes: 0 additions & 2 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@

#include "controller_manager/controller_manager.hpp"

#include <list>
#include <memory>
#include <string>
#include <utility>
Expand All @@ -24,7 +23,6 @@
#include "controller_manager_msgs/msg/hardware_component_state.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/version.h"
#include "rclcpp_lifecycle/state.hpp"

Expand Down
2 changes: 0 additions & 2 deletions controller_manager/src/ros2_control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <algorithm>
#include <chrono>
#include <memory>
#include <string>
#include <thread>

#include "controller_manager/controller_manager.hpp"
#include "rclcpp/rclcpp.hpp"
#include "realtime_tools/thread_priority.hpp"

using namespace std::chrono_literals;
Expand Down
4 changes: 0 additions & 4 deletions controller_manager/test/controller_manager_test_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,22 +22,18 @@
#include <memory>
#include <string>
#include <thread>
#include <utility>
#include <vector>

#include "controller_interface/controller_interface.hpp"

#include "controller_manager/controller_manager.hpp"
#include "controller_manager_msgs/srv/list_hardware_interfaces.hpp"
#include "controller_manager_msgs/srv/switch_controller.hpp"

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/utilities.hpp"

#include "std_msgs/msg/string.hpp"

#include "ros2_control_test_assets/descriptions.hpp"
#include "test_controller_failed_init/test_controller_failed_init.hpp"

namespace
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#include "test_controller.hpp"

#include <limits>
#include <memory>
#include <string>

#include "lifecycle_msgs/msg/state.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#ifndef TEST_CONTROLLER__TEST_CONTROLLER_HPP_
#define TEST_CONTROLLER__TEST_CONTROLLER_HPP_

#include <memory>
#include <string>
#include <vector>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,6 @@

#include "test_controller_failed_init.hpp"

#include <memory>
#include <string>

#include "lifecycle_msgs/msg/transition.hpp"

namespace test_controller_failed_init
{
TestControllerFailedInit::TestControllerFailedInit() : controller_interface::ControllerInterface()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,7 @@
#ifndef TEST_CONTROLLER_FAILED_INIT__TEST_CONTROLLER_FAILED_INIT_HPP_
#define TEST_CONTROLLER_FAILED_INIT__TEST_CONTROLLER_FAILED_INIT_HPP_

#include <memory>
#include <string>

#include "controller_manager/controller_manager.hpp"
#include "controller_interface/controller_interface.hpp"
#include "controller_manager/visibility_control.h"

namespace test_controller_failed_init
Expand Down
2 changes: 0 additions & 2 deletions controller_manager/test/test_controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,9 @@
#include <gmock/gmock.h>
#include <memory>
#include <string>
#include <utility>
#include <vector>

#include "controller_manager/controller_manager.hpp"
#include "controller_manager_msgs/srv/list_controllers.hpp"
#include "controller_manager_test_common.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "test_controller/test_controller.hpp"
Expand Down
1 change: 0 additions & 1 deletion controller_manager/test/test_controller_manager_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
#include "controller_manager_test_common.hpp"

#include "controller_interface/controller_interface.hpp"
#include "controller_manager/controller_manager.hpp"
#include "controller_manager_msgs/srv/list_controller_types.hpp"
#include "controller_manager_msgs/srv/list_controllers.hpp"
#include "controller_manager_msgs/srv/list_hardware_interfaces.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,13 +15,10 @@
#include <gtest/gtest.h>
#include <memory>
#include <string>
#include <utility>
#include <vector>

#include "controller_manager/controller_manager.hpp"
#include "controller_manager_msgs/srv/list_controllers.hpp"
#include "controller_manager_test_common.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "test_controller/test_controller.hpp"

using ::testing::_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,6 @@

#include "test_controller_with_interfaces.hpp"

#include <memory>
#include <string>

#include "lifecycle_msgs/msg/transition.hpp"

namespace test_controller_with_interfaces
{
TestControllerWithInterfaces::TestControllerWithInterfaces()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,8 @@
#ifndef TEST_CONTROLLER_WITH_INTERFACES__TEST_CONTROLLER_WITH_INTERFACES_HPP_
#define TEST_CONTROLLER_WITH_INTERFACES__TEST_CONTROLLER_WITH_INTERFACES_HPP_

#include <memory>
#include <string>

#include "controller_interface/visibility_control.h"
#include "controller_manager/controller_manager.hpp"
#include "controller_interface/controller_interface.hpp"
#include "controller_manager/visibility_control.h"

namespace test_controller_with_interfaces
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,9 @@
#include <utility>
#include <vector>

#include "controller_interface/controller_interface.hpp"
#include "controller_manager/controller_manager.hpp"
#include "controller_manager_msgs/srv/list_controllers.hpp"
#include "controller_manager_test_common.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/parameter.hpp"
#include "test_chainable_controller/test_chainable_controller.hpp"
#include "test_controller/test_controller.hpp"

Expand Down
1 change: 0 additions & 1 deletion controller_manager/test/test_hardware_management_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@

#include "controller_manager/controller_manager.hpp"
#include "controller_manager_msgs/msg/hardware_component_state.hpp"
#include "controller_manager_msgs/srv/list_controllers.hpp"
#include "controller_manager_msgs/srv/set_hardware_component_state.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/test/test_load_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,11 @@
#include <tuple>
#include <vector>

#include "controller_interface/controller_interface.hpp"
#include "controller_manager/controller_manager.hpp"
#include "controller_manager_test_common.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "test_controller/test_controller.hpp"
#include "test_controller_failed_init/test_controller_failed_init.hpp"

using test_controller::TEST_CONTROLLER_CLASS_NAME;
using ::testing::_;
Expand Down
2 changes: 0 additions & 2 deletions controller_manager/test/test_release_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,9 @@

#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <memory>
#include <string>
#include <vector>

#include "controller_interface/controller_interface.hpp"
#include "controller_manager/controller_manager.hpp"
#include "controller_manager_test_common.hpp"
#include "lifecycle_msgs/msg/state.hpp"
Expand Down
1 change: 0 additions & 1 deletion controller_manager/test/test_spawner_unspawner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#include <string>
#include <vector>

#include "controller_interface/controller_interface.hpp"
#include "controller_manager/controller_manager.hpp"
#include "controller_manager_test_common.hpp"
#include "lifecycle_msgs/msg/state.hpp"
Expand Down
3 changes: 2 additions & 1 deletion hardware_interface/include/hardware_interface/actuator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,13 @@
#include <string>
#include <vector>

#include "hardware_interface/actuator_interface.hpp"
#include "hardware_interface/handle.hpp"
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "hardware_interface/visibility_control.h"
#include "rclcpp/duration.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp_lifecycle/state.hpp"
Expand Down
Loading

0 comments on commit 6631270

Please sign in to comment.