Question about verifying joint value from ik solver

I found that the joint value from ik solver is not the same when I verified it with fk solver.

I created a joint it can rotate with X axis, and the end point of the chain is (0, 0, 1). Then I set joint value -1.57 (90 degrees clockwise)in fk solver, the answer is

[1, 0, 0 ,0, 0.000796274, 1 ,0, -1, 0.000796274] [ 0, 1, 0.000796274] Success, thanks KDL!

But when I set this position (0, 1, 0.000796274) in ik solver, I got the joint value is -0.738765. I think the answer should be -1.57, but it is not. Is there anything wrong in my testing procedure or in my codes? (my codes below are almost from KDL example http://www.orocos.org/kdl/examples) Thanks a lot for your help!!

fksolver.cpp
==================================================================
int main( int argc, char** argv ) {
    KDL::Chain chain;
    chain.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,1.0))));

    // Create solver based on kinematic chain
    ChainFkSolverPos_recursive fksolver = ChainFkSolverPos_recursive(chain);

    // Create joint array
    unsigned int nj = chain.getNrOfJoints();
    KDL::JntArray jointpositions = JntArray(nj);

    // Assign some values to the joint positions
    for(unsigned int i=0;i<nj;i++){
        float myinput;
        printf ("Enter the position of joint %i: ",i);
        scanf ("%e",&myinput);
        jointpositions(i)=(double)myinput;
    }

    // Create the frame that will contain the results
    KDL::Frame cartpos;
    // Calculate forward position kinematics
    bool kinematics_status;
    kinematics_status = fksolver.JntToCart(jointpositions,cartpos);
    if(kinematics_status>=0){
        std::cout << cartpos <<std::endl;
        printf("%s \n","Success, thanks KDL!");
    }else{
        printf("%s \n","Error: could not calculate forward kinematics :(");
    }
}
================================================================================

iksolver.cpp

================================================================================

int main( int argc, char** argv ) {
    KDL::Chain chain;
    chain.addSegment(Segment(Joint(Joint::RotX),Frame(Vector(0.0,0.0,1.0))));
    //Creation of the solvers:
    ChainFkSolverPos_recursive fksolver1(chain);//Forward position solver
    ChainIkSolverVel_pinv iksolver1v(chain);//Inverse velocity solver
    ChainIkSolverPos_NR iksolver1(chain,fksolver1,iksolver1v,100,1e-6);//Maximum 100 iterations, stop at accuracy 1e-6

    //Creation of jntarrays:
    JntArray q(chain.getNrOfJoints());
    JntArray q_init(chain.getNrOfJoints());

    //Set destination frame
    Frame F_dest=Frame(Vector(0.0, 1.0, 0.000796274));

    int ret = iksolver1.CartToJnt(q_init,F_dest,q);
    for(int i=0; i<q.rows(); i++)
    {
        printf("value is %f\n", q(i,0));
    }
}
====================================================================