From d4f35b52cd9f4515666e8ead1bed26778d5b0bd7 Mon Sep 17 00:00:00 2001 From: liyixin135 <421159734@qq.com> Date: Thu, 23 Nov 2023 22:25:49 +0800 Subject: [PATCH] Remove info. --- rm_shooter_controllers/src/standard.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/rm_shooter_controllers/src/standard.cpp b/rm_shooter_controllers/src/standard.cpp index 8ae0ab60..66f0c09e 100644 --- a/rm_shooter_controllers/src/standard.cpp +++ b/rm_shooter_controllers/src/standard.cpp @@ -69,7 +69,6 @@ bool Controller::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& ro ros::NodeHandle nh_trigger = ros::NodeHandle(controller_nh, "trigger"); if (!controller_nh.getParam("offset", offset_)) { - ROS_INFO("one"); ros::NodeHandle nh_friction_l = ros::NodeHandle(controller_nh, "friction_left"); ros::NodeHandle nh_friction_r = ros::NodeHandle(controller_nh, "friction_right"); return ctrl_friction_l_.init(effort_joint_interface_, nh_friction_l) && @@ -78,7 +77,6 @@ bool Controller::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& ro } else { - ROS_INFO("double"); is_double_stage = true; ros::NodeHandle nh_friction_l_f = ros::NodeHandle(controller_nh, "friction_left_front"); ros::NodeHandle nh_friction_r_f = ros::NodeHandle(controller_nh, "friction_right_front");