Skip to content

Commit 27f5291

Browse files
authored
Remove the use of visibility macros (#679)
1 parent e23a12a commit 27f5291

File tree

2 files changed

+1
-12
lines changed

2 files changed

+1
-12
lines changed

example_7/controller/include/ros2_control_demo_example_7/r6bot_controller.hpp

-11
Original file line numberDiff line numberDiff line change
@@ -42,43 +42,32 @@ namespace ros2_control_demo_example_7
4242
class RobotController : public controller_interface::ControllerInterface
4343
{
4444
public:
45-
CONTROLLER_INTERFACE_PUBLIC
4645
RobotController();
4746

48-
CONTROLLER_INTERFACE_PUBLIC
4947
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
5048

51-
CONTROLLER_INTERFACE_PUBLIC
5249
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
5350

54-
CONTROLLER_INTERFACE_PUBLIC
5551
controller_interface::return_type update(
5652
const rclcpp::Time & time, const rclcpp::Duration & period) override;
5753

58-
CONTROLLER_INTERFACE_PUBLIC
5954
controller_interface::CallbackReturn on_init() override;
6055

61-
CONTROLLER_INTERFACE_PUBLIC
6256
controller_interface::CallbackReturn on_configure(
6357
const rclcpp_lifecycle::State & previous_state) override;
6458

65-
CONTROLLER_INTERFACE_PUBLIC
6659
controller_interface::CallbackReturn on_activate(
6760
const rclcpp_lifecycle::State & previous_state) override;
6861

69-
CONTROLLER_INTERFACE_PUBLIC
7062
controller_interface::CallbackReturn on_deactivate(
7163
const rclcpp_lifecycle::State & previous_state) override;
7264

73-
CONTROLLER_INTERFACE_PUBLIC
7465
controller_interface::CallbackReturn on_cleanup(
7566
const rclcpp_lifecycle::State & previous_state) override;
7667

77-
CONTROLLER_INTERFACE_PUBLIC
7868
controller_interface::CallbackReturn on_error(
7969
const rclcpp_lifecycle::State & previous_state) override;
8070

81-
CONTROLLER_INTERFACE_PUBLIC
8271
controller_interface::CallbackReturn on_shutdown(
8372
const rclcpp_lifecycle::State & previous_state) override;
8473

example_7/doc/userdoc.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -207,7 +207,7 @@ There are more methods that can be implemented for lifecycle changes, but they a
207207
using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
208208
#include "hardware_interface/types/hardware_interface_return_values.hpp"
209209

210-
class HARDWARE_INTERFACE_PUBLIC RobotSystem : public hardware_interface::SystemInterface {
210+
class RobotSystem : public hardware_interface::SystemInterface {
211211
public:
212212
CallbackReturn on_init(const hardware_interface::HardwareInfo &info) override;
213213
CallbackReturn on_configure(const rclcpp_lifecycle::State & previous_state) override;

0 commit comments

Comments
 (0)