Open UltronDestroyer opened 9 years ago
Why is it only looking for one joint?
The controller only works for grippers with one actuated dof.
Shouldn't it be taking an array of joints or is it specifically looking for the ee_joint?
There is currently no open-source alternative for multi-dof graspers. We have rolled our own multi-dof controller (developed independently from this one) but it's proprietary.
If it's using the ee_joint, I'm not sure what to put in the .yaml config as there's no docs anywhere.
You should specify the name of the actuated gripper joint, but I guess you already know that by now. I imagine you have a multi-dof grasper.
Ahhh, yah the robotiq gripper is multi-dof.. that's unfortunate since I have no skills in writing controllers.
"There is currently no open-source alternative for multi-dof graspers."
Yikes. Alright, this helps alot. Thank you Adolfo.
You could use a joint trajectory controller that addresses all the joints in the gripper - are there particular features you are looking for in this controller that would not be addressed by the joint trajectory controller (maybe force/torque clamping)?
Can you shed some light on the gripper_action_controller for me Adolfo?
Specifically, I don't believe this is implemented correctly: (Starting at line 151 of this file https://github.com/ros-controls/ros_controllers/blob/indigo-devel/gripper_action_controller/include/gripper_action_controller/gripper_action_controller_impl.h)
Why is it only looking for one joint? Shouldn't it be taking an array of joints or is it specifically looking for the ee_joint? If it's using the ee_joint, I'm not sure what to put in the .yaml config as there's no docs anywhere.
// Controlled joint controllernh.getParam("joint", jointname); if (jointname.empty()) { ROS_ERROR_STREAMNAMED(name, "Could not find joint name on param server"); return false; } // URDF joints boost::shared_ptrurdf::Model urdf = getUrdf(root_nh, "robot_description"); if (!urdf) { return false; } std::vectorstd::string joint_names; joint_names.push_back(jointname); std::vector urdf_joints = getUrdfJoints(*urdf, joint_names);
if (urdfjoints.empty())
{
return false;
}
// Initialize members
// Joint handle
try
{
joint = hw->getHandle(jointname);
}
catch (...)
{
ROS_ERROR_STREAMNAMED(name, "Could not find joint '" << jointname << "' in '" <<
this->getHardwareInterfaceType() << "'.");
return false;
}
ROS_DEBUG_STREAMNAMED(name, "Initialized controller '" << name_ << "' with:" <<
"\n- Hardware interface type: '" << this->getHardwareInterfaceType() << "'" <<
"\n");