From 800d1237eae9822712e93b5b7213065726a3db1a Mon Sep 17 00:00:00 2001 From: rickstaa Date: Mon, 4 Oct 2021 11:21:47 +0200 Subject: [PATCH] BREAKiNG CHANGE: Moves 'resting_threshold' and 'consecutive_samples' to base ns This commit mose the `resting_threshold` and `consecutive_samples` to the base ns since they also apply to the `gripper_action` action server (see #172). --- franka_gazebo/include/franka_gazebo/franka_gripper_sim.h | 4 ++-- franka_gazebo/src/franka_gripper_sim.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/franka_gazebo/include/franka_gazebo/franka_gripper_sim.h b/franka_gazebo/include/franka_gazebo/franka_gripper_sim.h index 4df7c6605..1e4914679 100644 --- a/franka_gazebo/include/franka_gazebo/franka_gripper_sim.h +++ b/franka_gazebo/include/franka_gazebo/franka_gripper_sim.h @@ -32,10 +32,10 @@ const double kDefaultGripperActionWidthTolerance = 0.005; /// How fast shall the gripper execute gripper command actions? [m/s] const double kDefaultGripperActionSpeed = 0.1; -/// Below which speed the target width should be checked to abort or succeed the grasp action [m/s] +/// Below which speed the target width should be checked to abort or succeed the grasp/gripper action [m/s] const double kGraspRestingThreshold = 0.001; -/// How many times the speed has to drop below resting threshold before the grasping will be checked +/// How many times the speed has to drop below resting threshold before the grasping/gripper action will be checked const int kGraspConsecutiveSamples = 3; /** diff --git a/franka_gazebo/src/franka_gripper_sim.cpp b/franka_gazebo/src/franka_gripper_sim.cpp index 96aca3de1..c9d4d32ca 100644 --- a/franka_gazebo/src/franka_gripper_sim.cpp +++ b/franka_gazebo/src/franka_gripper_sim.cpp @@ -29,8 +29,8 @@ bool FrankaGripperSim::init(hardware_interface::EffortJointInterface* hw, ros::N nh.param("gripper_action/width_tolerance", this->tolerance_gripper_action_, kDefaultGripperActionWidthTolerance); nh.param("gripper_action/speed", this->speed_default_, kDefaultGripperActionSpeed); - nh.param("grasp/resting_threshold", this->speed_threshold_, kGraspRestingThreshold); - nh.param("grasp/consecutive_samples", this->speed_samples_, kGraspConsecutiveSamples); + nh.param("resting_threshold", this->speed_threshold_, kGraspRestingThreshold); + nh.param("consecutive_samples", this->speed_samples_, kGraspConsecutiveSamples); try { this->finger1_ = hw->getHandle(finger1);