Skip to content

Commit 5b1771d

Browse files
committed
Remove visibility macros from the test controller
1 parent 9f56e52 commit 5b1771d

File tree

1 file changed

+0
-8
lines changed

1 file changed

+0
-8
lines changed

controller_manager/test/test_controller_failed_activate/test_controller_failed_activate.hpp

Lines changed: 0 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@
1818
#include <memory>
1919
#include <string>
2020

21-
#include "controller_interface/visibility_control.h"
2221
#include "controller_manager/controller_manager.hpp"
2322

2423
namespace test_controller_failed_activate
@@ -31,10 +30,8 @@ constexpr char TEST_CONTROLLER_COMMAND_INTERFACE[] = "joint2/velocity";
3130
class TestControllerFailedActivate : public controller_interface::ControllerInterface
3231
{
3332
public:
34-
CONTROLLER_MANAGER_PUBLIC
3533
TestControllerFailedActivate();
3634

37-
CONTROLLER_MANAGER_PUBLIC
3835
virtual ~TestControllerFailedActivate() = default;
3936

4037
controller_interface::InterfaceConfiguration command_interface_configuration() const override
@@ -50,22 +47,17 @@ class TestControllerFailedActivate : public controller_interface::ControllerInte
5047
controller_interface::interface_configuration_type::NONE};
5148
}
5249

53-
CONTROLLER_MANAGER_PUBLIC
5450
controller_interface::return_type update(
5551
const rclcpp::Time & time, const rclcpp::Duration & period) override;
5652

57-
CONTROLLER_MANAGER_PUBLIC
5853
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_init() override;
5954

60-
CONTROLLER_MANAGER_PUBLIC
6155
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(
6256
const rclcpp_lifecycle::State & previous_state) override;
6357

64-
CONTROLLER_MANAGER_PUBLIC
6558
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(
6659
const rclcpp_lifecycle::State & previous_state) override;
6760

68-
CONTROLLER_MANAGER_PUBLIC
6961
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup(
7062
const rclcpp_lifecycle::State & previous_state) override;
7163
};

0 commit comments

Comments
 (0)