diff --git a/franka_example_controllers/include/franka_example_controllers/cartesian_pose_example_controller.h b/franka_example_controllers/include/franka_example_controllers/cartesian_pose_example_controller.h
index e66503a5443fc7f073710ccf9e2ba39c51b93107..e712c7a88c301a531ac214ecb09ec5ad7ccab831 100644
--- a/franka_example_controllers/include/franka_example_controllers/cartesian_pose_example_controller.h
+++ b/franka_example_controllers/include/franka_example_controllers/cartesian_pose_example_controller.h
@@ -20,9 +20,7 @@ class CartesianPoseExampleController
     : public controller_interface::MultiInterfaceController<franka_hw::FrankaPoseCartesianInterface,
                                                             franka_hw::FrankaStateInterface> {
  public:
-  bool init(hardware_interface::RobotHW* robot_hardware,
-            ros::NodeHandle& root_node_handle,
-            ros::NodeHandle& /* controller_node_handle */) override;
+  bool init(hardware_interface::RobotHW* robot_hardware, ros::NodeHandle& node_handle) override;
   void starting(const ros::Time&) override;
   void update(const ros::Time&, const ros::Duration& period) override;
 
diff --git a/franka_example_controllers/include/franka_example_controllers/cartesian_velocity_example_controller.h b/franka_example_controllers/include/franka_example_controllers/cartesian_velocity_example_controller.h
index 15d4970b63fb46757908e4d96aaa06dfd6c588dd..95d4ace9a9e438d98e684fc1716b86487e793b17 100644
--- a/franka_example_controllers/include/franka_example_controllers/cartesian_velocity_example_controller.h
+++ b/franka_example_controllers/include/franka_example_controllers/cartesian_velocity_example_controller.h
@@ -18,9 +18,7 @@ class CartesianVelocityExampleController : public controller_interface::MultiInt
                                                franka_hw::FrankaVelocityCartesianInterface,
                                                franka_hw::FrankaStateInterface> {
  public:
-  bool init(hardware_interface::RobotHW* robot_hardware,
-            ros::NodeHandle& root_node_handle,
-            ros::NodeHandle& /* controller_node_handle */) override;
+  bool init(hardware_interface::RobotHW* robot_hardware, ros::NodeHandle& node_handle) override;
   void update(const ros::Time&, const ros::Duration& period) override;
   void starting(const ros::Time&) override;
   void stopping(const ros::Time&) override;
diff --git a/franka_example_controllers/src/cartesian_pose_example_controller.cpp b/franka_example_controllers/src/cartesian_pose_example_controller.cpp
index 4389fa0721909b1656eac1962cbd30b0aca9a5b1..ae1b787aa97fe89d8ce80a028a02a698600b95d4 100644
--- a/franka_example_controllers/src/cartesian_pose_example_controller.cpp
+++ b/franka_example_controllers/src/cartesian_pose_example_controller.cpp
@@ -15,8 +15,7 @@
 namespace franka_example_controllers {
 
 bool CartesianPoseExampleController::init(hardware_interface::RobotHW* robot_hardware,
-                                          ros::NodeHandle& root_node_handle,
-                                          ros::NodeHandle& /* controller_node_handle */) {
+                                          ros::NodeHandle& node_handle) {
   cartesian_pose_interface_ = robot_hardware->get<franka_hw::FrankaPoseCartesianInterface>();
   if (cartesian_pose_interface_ == nullptr) {
     ROS_ERROR(
@@ -26,7 +25,7 @@ bool CartesianPoseExampleController::init(hardware_interface::RobotHW* robot_har
   }
 
   std::string arm_id;
-  if (!root_node_handle.getParam("arm_id", arm_id)) {
+  if (!node_handle.getParam("arm_id", arm_id)) {
     ROS_ERROR("CartesianPoseExampleController: Could not get parameter arm_id");
     return false;
   }
diff --git a/franka_example_controllers/src/cartesian_velocity_example_controller.cpp b/franka_example_controllers/src/cartesian_velocity_example_controller.cpp
index ad7b64bd87f9d24f5f736f8791c5aa390ac17c94..59e0f6fedbf02a3d85d5884e74c36780694c8d95 100644
--- a/franka_example_controllers/src/cartesian_velocity_example_controller.cpp
+++ b/franka_example_controllers/src/cartesian_velocity_example_controller.cpp
@@ -15,10 +15,9 @@
 namespace franka_example_controllers {
 
 bool CartesianVelocityExampleController::init(hardware_interface::RobotHW* robot_hardware,
-                                              ros::NodeHandle& root_node_handle,
-                                              ros::NodeHandle& /* controller_node_handle */) {
+                                              ros::NodeHandle& node_handle) {
   std::string arm_id;
-  if (!root_node_handle.getParam("arm_id", arm_id)) {
+  if (!node_handle.getParam("arm_id", arm_id)) {
     ROS_ERROR("CartesianVelocityExampleController: Could not get parameter arm_id");
     return false;
   }