Open taichiH opened 6 years ago
can you elaborate more on how you tested this? are you sure you're a applying a valid I.K. position? For example, you can set a random pose and get the index pose from
auto p = robot->getEEFPosition(aero::rarm, aero::eef::index);
auto q = robot->getEEFOrientation(aero::rarm, aero::eef::index);
auto goal = aero::Translation(p) * q;
Does applying this sort of goal work? Note, that just changing the argument in the sample code has no guarantee that there is a solution for the index finger. Those values are only checked with aero::eef::grasp.
First, I send reset_manip pose and check r_index_tip_link pose using tf_echo.
rosrun tf tf_echo /base_link /r_index_tip_link
Second, set pose and orientation got from tf_echo to aero::eef::index IK goal. This mean I set pose same as reset-manip pose. so this inverse-kinematics should solved but not found solution.
I tried way you explained above but result is also not good. Simple code shown below.
@YoheiKakiuchi said this problem may be occurred because index joint is not fix-joint.
#include <aero_std/AeroMoveitInterface.hh>
int main(int argc, char **argv)
{
ros::init(argc, argv, "ik_sample_node");
ros::NodeHandle nh;
aero::interface::AeroMoveitInterface::Ptr robot(new aero::interface::AeroMove\
itInterface(nh));
ROS_INFO("reseting robot pose");
robot->setPoseVariables(aero::pose::reset_manip);
robot->sendModelAngles(3000);
sleep(3);
auto p = robot->getEEFPosition(aero::arm::rarm, aero::eef::index);
auto q = robot->getEEFOrientation(aero::arm::rarm, aero::eef::index);
auto goal = aero::Translation(p) * q;
bool r_ik_result = robot->setFromIK(aero::arm::rarm, aero::ikrange::wholebody, goal, aero::eef::index);
if (r_ik_result) {
ROS_INFO("ik success !");
robot->sendModelAngles(3000);
sleep(3);
} else {
ROS_WARN("ik failed");
}
ROS_INFO("demo node finished");
ros::shutdown();
return 0;
}
OK, I think this is a valid problem.
In the meantime, I think the only way to get along with this, is to convert index poses to grasp/hand poses and solve ik with eef::grasp or eef::hand. As I see maintenance problems with aero::eef not being stable for some functions (e.g. #337 where planning with grasp_link does not work with indigo), I would recommend the api to remove eef options and solve everything with eef::hand only; and instead have a conversion function between eefs as in #333)
@sasabot
aero::eef::index
existed at v1.0.0, Did anyone use it ?
Did it not work well at that time?
checked some of my old codes but none of them were using aero::eef::index.
it seems that I always solved with aero::eef::grasp. every time I wanted to solve for aero::eef::index, I first solved the IK, then called getEEFPosition(aero::eef::index), and used the lifter to adjust the finger tip position.
I'd like to solve IK but always IK failed, when I set aero::eef::index argument to setFromIK. Is this failure only this version or we couldn't solve index_tip_link IK from before?
I show the log below.