Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Revert robotiq_gripper_controller type until antipodal controller becomes available #48

Merged
merged 2 commits into from
Mar 4, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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: antipodal_gripper_action_controller/GripperActionController
type: position_controllers/GripperActionController
robotiq_activation_controller:
type: robotiq_controllers/RobotiqActivationController

Expand Down
16 changes: 8 additions & 8 deletions robotiq_driver/include/robotiq_driver/hardware_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,24 +140,24 @@ class RobotiqGripperHardwareInterface : public hardware_interface::SystemInterfa
std::atomic<bool> communication_thread_is_running_;
void background_task();

double gripper_closed_pos_;
double gripper_closed_pos_ = 0.0;

static constexpr double NO_NEW_CMD_ = std::numeric_limits<double>::quiet_NaN();

double gripper_position_;
double gripper_velocity_;
double gripper_position_command_;
double gripper_position_ = 0.0;
double gripper_velocity_ = 0.0;
double gripper_position_command_ = 0.0;

std::atomic<uint8_t> write_command_;
std::atomic<uint8_t> write_force_;
std::atomic<uint8_t> write_speed_;
std::atomic<uint8_t> gripper_current_state_;

double reactivate_gripper_cmd_;
double reactivate_gripper_cmd_ = 0.0;
std::atomic<bool> reactivate_gripper_async_cmd_;
double reactivate_gripper_response_;
double gripper_force_;
double gripper_speed_;
double reactivate_gripper_response_ = 0.0;
double gripper_force_ = 0.0;
double gripper_speed_ = 0.0;
std::atomic<std::optional<bool>> reactivate_gripper_async_response_;
};

Expand Down
Loading