From f9a5a66b4ebdd3f7391d3d51c6582f504989418c Mon Sep 17 00:00:00 2001 From: Paul Gesel Date: Tue, 13 Feb 2024 09:20:29 -0700 Subject: [PATCH] update parameters Signed-off-by: Paul Gesel --- .../antipodal_gripper_action_controller_impl.hpp | 6 +++--- ...tipodal_gripper_action_controller_parameters.yaml | 12 ++++++++++-- 2 files changed, 13 insertions(+), 5 deletions(-) diff --git a/antipodal_gripper_controller/include/antipodal_gripper_controller/antipodal_gripper_action_controller_impl.hpp b/antipodal_gripper_controller/include/antipodal_gripper_controller/antipodal_gripper_action_controller_impl.hpp index 97fe6c5300..8b5243fd40 100644 --- a/antipodal_gripper_controller/include/antipodal_gripper_controller/antipodal_gripper_action_controller_impl.hpp +++ b/antipodal_gripper_controller/include/antipodal_gripper_controller/antipodal_gripper_action_controller_impl.hpp @@ -114,7 +114,7 @@ void GripperActionController::accepted_callback( } else { - command_struct_.max_velocity_ = 0.0; + command_struct_.max_velocity_ = params_.max_velocity; } if (params_.use_effort_interface && !goal_handle->get_goal()->command.effort.empty()) { @@ -169,8 +169,8 @@ rclcpp_action::CancelResponse GripperActionController::cancel_callback( void GripperActionController::set_hold_position() { command_struct_.position_cmd_ = joint_position_state_interface_->get().get_value(); - command_struct_.max_velocity_ = 0.0; command_struct_.max_effort_ = params_.max_effort; + command_struct_.max_velocity_ = params_.max_velocity; command_.writeFromNonRT(command_struct_); } @@ -328,7 +328,7 @@ controller_interface::CallbackReturn GripperActionController::on_activate( // Command - non RT version command_struct_.position_cmd_ = joint_position_state_interface_->get().get_value(); command_struct_.max_effort_ = params_.max_effort; - command_struct_.max_velocity_ = 0.0; + command_struct_.max_velocity_ = params_.max_velocity; command_.initRT(command_struct_); // Result diff --git a/antipodal_gripper_controller/src/antipodal_gripper_action_controller_parameters.yaml b/antipodal_gripper_controller/src/antipodal_gripper_action_controller_parameters.yaml index fca6890787..5c785fb710 100644 --- a/antipodal_gripper_controller/src/antipodal_gripper_action_controller_parameters.yaml +++ b/antipodal_gripper_controller/src/antipodal_gripper_action_controller_parameters.yaml @@ -20,8 +20,16 @@ antipodal_gripper_action_controller: } max_effort: { type: double, - default_value: 0.0, - description: "Max allowable effort", + default_value: 10.0, + description: "Default effort used for grasping (Newtons)", + validation: { + gt_eq: [ 0.0 ] + }, + } + max_velocity: { + type: double, + default_value: 0.1, + description: "Default target velocity used for grasping (meters/second)", validation: { gt_eq: [ 0.0 ] },