Skip to content
Open
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
1 change: 1 addition & 0 deletions issue.json
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
{"author":{"id":"U_kgDOC7hpFQ","is_bot":false,"login":"nicco99-prog","name":""},"body":"I would like to customize my Kinova robot by equipping it with a different end-effector instead of the Robotiq grippers. I already have the URDF and Xacro files for this end-effector, and I’d like to use MoveIt to control my robot outside of simulation. Do you have any suggestions?\nEven when I try to remove the gripper and use only the kinova robot without the gripper, I get this kind of error:\n[ros2_control_node-1] [ERROR] [1747672075.483567156] [KortexMultiInterfaceHardware]: Gripper joint name is empty!\n\nPS: Running on ROS2 Jazzy, Ubuntu 24.04\n","labels":[{"id":"LA_kwDOF0UnJs8AAAAB_nQZaA","name":"updated","description":"There is an update on the issue that was not addressed","color":"DA3250"}],"number":287,"title":"Use MoveIt with a different end-effector in place of the Robotiq grippers","url":"https://github.com/Kinovarobotics/ros2_kortex/issues/287"}
40 changes: 21 additions & 19 deletions kortex_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -170,16 +170,15 @@ CallbackReturn KortexMultiInterfaceHardware::on_init(
gripper_joint_name_ = info_.hardware_parameters["gripper_joint_name"];
if (gripper_joint_name_.empty())
{
RCLCPP_ERROR(LOGGER, "Gripper joint name is empty!");
RCLCPP_INFO(LOGGER, "No gripper joint name provided, gripper control will be disabled.");
}
else
{
RCLCPP_INFO(LOGGER, "Gripper joint name is '%s'", gripper_joint_name_.c_str());
gripper_command_max_velocity_ = std::stod(info_.hardware_parameters["gripper_max_velocity"]);
gripper_command_max_force_ = std::stod(info_.hardware_parameters["gripper_max_force"]);
}

gripper_command_max_velocity_ = std::stod(info_.hardware_parameters["gripper_max_velocity"]);
gripper_command_max_force_ = std::stod(info_.hardware_parameters["gripper_max_force"]);

RCLCPP_INFO_STREAM(LOGGER, "Connecting to robot at " << robot_ip);

// connections
Expand Down Expand Up @@ -667,21 +666,24 @@ CallbackReturn KortexMultiInterfaceHardware::on_activate(
base_command_.add_actuators()->set_position(base_feedback.actuators(i).position());
}

// Initialize gripper
float gripper_initial_position =
base_feedback.interconnect().gripper_feedback().motor()[0].position();
RCLCPP_INFO(LOGGER, "Gripper initial position is '%f'.", gripper_initial_position);

// to radians
gripper_command_position_ = gripper_initial_position / 100.0 * 0.81;

// Initialize interconnect command to current gripper position.
base_command_.mutable_interconnect()->mutable_command_id()->set_identifier(0);
gripper_motor_command_ =
base_command_.mutable_interconnect()->mutable_gripper_command()->add_motor_cmd();
gripper_motor_command_->set_position(gripper_initial_position); // % position
gripper_motor_command_->set_velocity(gripper_speed_command_); // % speed
gripper_motor_command_->set_force(gripper_force_command_); // % force
// Initialize gripper if internal bus communication is enabled
if (use_internal_bus_gripper_comm_)
{
float gripper_initial_position =
base_feedback.interconnect().gripper_feedback().motor()[0].position();
RCLCPP_INFO(LOGGER, "Gripper initial position is '%f'.", gripper_initial_position);

// to radians
gripper_command_position_ = gripper_initial_position / 100.0 * 0.81;

// Initialize interconnect command to current gripper position.
base_command_.mutable_interconnect()->mutable_command_id()->set_identifier(0);
gripper_motor_command_ =
base_command_.mutable_interconnect()->mutable_gripper_command()->add_motor_cmd();
gripper_motor_command_->set_position(gripper_initial_position); // % position
gripper_motor_command_->set_velocity(gripper_speed_command_); // % speed
gripper_motor_command_->set_force(gripper_force_command_); // % force
}

// Send a first frame
base_feedback = base_cyclic_.Refresh(base_command_);
Expand Down