From 4bbcd60af75a725ef87b7255e610cc3f2d6b3a0a Mon Sep 17 00:00:00 2001 From: Florian Walch <florian.walch@franka.de> Date: Tue, 20 Mar 2018 16:49:59 +0100 Subject: [PATCH] Update Cartesian example controllers --- .../cartesian_pose_example_controller.h | 4 +--- .../cartesian_velocity_example_controller.h | 4 +--- .../src/cartesian_pose_example_controller.cpp | 5 ++--- .../src/cartesian_velocity_example_controller.cpp | 5 ++--- 4 files changed, 6 insertions(+), 12 deletions(-) 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 e66503a..e712c7a 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 15d4970..95d4ace 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 4389fa0..ae1b787 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 ad7b64b..59e0f6f 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; } -- GitLab