Using setJointValueTarget and setPoseTarget have different results
The following code works, if the target is defined by Joint Value. But if I define the same point by Pose (as in the comment section), the planning path is different every time I run the code. And some times the robot is not able to find the path...
I am using hydro on UR10, moveit version is 0.5.20. ubuntu 12.04. I get the position and orientation value of 'goal' by using command: rosrun tf tf_echo base_link ee_link
, when the end effector reach 'joints'.
So basically, 'goal' and 'joints' are the same position. Why setJointValueTarge
is working while setPoseTarget
is not?
int main(int argc, char **argv)
{
ros::init(argc, argv, "move_group_test");
ros::AsyncSpinner spinner(1);
spinner.start();
moveit::planning_interface::MoveGroup group("manipulator");
group.setPlannerId("ESTkConfigDefault");
std::map<std::string, double> joints;
joints["shoulder_pan_joint"] = 0;
joints["shoulder_lift_joint"] = -0.5648;
joints["elbow_joint"] = -1.06;
joints["wrist_1_joint"] = -1.69;
joints["wrist_2_joint"] = -1.76;
joints["wrist_3_joint"] = 8.572;
group.setJointValueTarget(joints);
group.move();
/*
geometry_msgs::Pose goal;
goal.position.x = 0.555;
goal.position.y = 0.146;
goal.position.z = 1.156;
goal.orientation.w = 0.991428;
goal.orientation.x = 0.0085588;
goal.orientation.y = -0.087665;
goal.orientation.z = -0.0964952;
group.setPoseTarget(goal);
group.move();
*/
}
I have a similar issue, did you find any answers?