Skip to content

Commit df16a76

Browse files
committed
Use forward declaration for ParamListener
1 parent 2ce3fe0 commit df16a76

File tree

2 files changed

+3
-2
lines changed

2 files changed

+3
-2
lines changed

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -48,10 +48,9 @@
4848
#include "rclcpp/node.hpp"
4949
#include "std_msgs/msg/string.hpp"
5050

51-
#include "controller_manager_parameters.hpp"
52-
5351
namespace controller_manager
5452
{
53+
class ParamListener;
5554
using ControllersListIterator = std::vector<controller_manager::ControllerSpec>::const_iterator;
5655

5756
CONTROLLER_MANAGER_PUBLIC rclcpp::NodeOptions get_cm_node_options();

controller_manager/src/controller_manager.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,8 @@
2828
#include "rclcpp/version.h"
2929
#include "rclcpp_lifecycle/state.hpp"
3030

31+
#include "controller_manager_parameters.hpp"
32+
3133
namespace // utility
3234
{
3335
static constexpr const char * kControllerInterfaceNamespace = "controller_interface";

0 commit comments

Comments
 (0)