Skip to content

Commit

Permalink
update config
Browse files Browse the repository at this point in the history
Signed-off-by: Paul Gesel <[email protected]>
  • Loading branch information
pac48 committed Feb 2, 2024
1 parent cea992f commit 0f14c5b
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
2 changes: 1 addition & 1 deletion robotiq_description/config/robotiq_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ controller_manager:
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
robotiq_gripper_controller:
type: position_controllers/GripperActionController
type: antipodal_gripper_action_controller/GripperActionController
robotiq_activation_controller:
type: robotiq_controllers/RobotiqActivationController

Expand Down
8 changes: 4 additions & 4 deletions robotiq_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ const auto kLogger = rclcpp::get_logger("RobotiqGripperHardwareInterface");

constexpr uint8_t kGripperMinPos = 3;
constexpr uint8_t kGripperMaxPos = 230;
constexpr double kGripperMaxSpeed = 0.150; //mm/s
constexpr double kGripperMaxforce = 235; // N
constexpr double kGripperMaxSpeed = 0.150; // mm/s
constexpr double kGripperMaxforce = 235; // N
constexpr uint8_t kGripperRange = kGripperMaxPos - kGripperMinPos;

constexpr auto kGripperCommsLoopPeriod = std::chrono::milliseconds{ 10 };
Expand Down Expand Up @@ -294,9 +294,9 @@ hardware_interface::return_type RobotiqGripperHardwareInterface::write(const rcl
double gripper_pos = (gripper_position_command_ / gripper_closed_pos_) * kGripperRange + kGripperMinPos;
gripper_pos = std::max(std::min(gripper_pos, 255.0), 0.0);
write_command_.store(uint8_t(gripper_pos));
gripper_speed_ = kGripperMaxSpeed*std::clamp(fabs(gripper_speed_)/kGripperMaxSpeed, 0.0, 1.0);
gripper_speed_ = kGripperMaxSpeed * std::clamp(fabs(gripper_speed_) / kGripperMaxSpeed, 0.0, 1.0);
write_speed_.store(uint8_t(gripper_speed_ * 0xFF));
gripper_force_ = kGripperMaxforce*std::clamp(fabs(gripper_force_)/kGripperMaxforce, 0.0, 1.0);
gripper_force_ = kGripperMaxforce * std::clamp(fabs(gripper_force_) / kGripperMaxforce, 0.0, 1.0);
write_force_.store(uint8_t(gripper_force_ * 0xFF));

return hardware_interface::return_type::OK;
Expand Down

0 comments on commit 0f14c5b

Please sign in to comment.