awkward difference in ChainIkSolverPos_NR vs ChainIkSolverPos_NR_JL

Hi,

Currently, I'm working on a project where I'm developing an offline robot programming software built on top of PyKDL and PythonOCC. The setup I'm working on involves a sturdy ABB 6400 on a 26 meter long track.

Now, there's a few things I don't grasp:

* first and foremost, the ChainIkSolverPos_NR solver can solve the motion with the integrated track, ChainIkSolverPos_NR_JL is does not use the linear track [ Segment(Joint( "cradle", Joint.TransX )) ]
* however, when I use the JntArray that the ChainIkSolverPos_NR outputs as an input for ChainIkSolverPos_NR_JL, than the solver can reach the frame. in other words, I'm led to believe that the frame should lie within the solvers reach so to speak.
* when reading the source code of both ChainIkSolverPos_NR and ChainIkSolverPos_NR_JL I cannot explain the considerable difference in results from the solvers… the only difference is 6 lines that keep the joints within range
* both the ChainIkSolverPos_NR and ChainIkSolverPos_NR_JL instance refer to the same FK and IK velocity solver ( ChainFkSolverPos_recursive, ChainIkSolverVel_pinv ), so that's not it either…
* leaving out the segment [ Segment(Joint( "track", Joint.TransZ ), Frame(Vector(0,0,track_offset_z))) ] didn't result in a difference in behaviour

Which leaves me run out of ideas how to tackle this issue.
Any suggestions what I might be getting wrong?
Basically, when when using the ChainIkSolverPos_NR solver, the linear track is part of the kinematic chain, while the movement is extremely limited when using the ChainIkSolverPos_NR_JL solver ( there is some movement, ~90mm when a displacement of ~10.000mm is required )

n_segments = 8
# joint array that set the lower and upper bounds of the joint angles
q_min, q_max = JntArray(n_segments), JntArray(n_segments)

fr1 = Frame().DH( 240., radians(-90.), 800., radians(0.0) )
fr2 = Frame().DH( 1050, radians(0.), 0., radians(-90.) )
fr3 = Frame().DH( 225., radians(-90.), 0., radians(0.) )
fr4 = Frame().DH( 0., radians(-90.), 1520, radians(180.) )
fr5 = Frame().DH( 0., radians(90.), 0., radians(0.) )
fr6 = Frame().DH( 0., radians(0.), 200., radians(0.) )

seg_track = Segment(Joint( "track", Joint.TransZ ), Frame(Vector(0,0,track_offset_z)))
seg_track_cradle = Segment(Joint( "cradle", Joint.TransX ))#,
seg1=Segment( Joint("joint-1", Joint.RotZ), fr1)
seg2=Segment( Joint("joint-2", Joint.RotZ), fr2)
seg3=Segment( Joint("joint-3", Joint.RotZ), fr3)
seg4=Segment( Joint("joint-4", Joint.RotZ), fr4)
seg5=Segment( Joint("joint-5", Joint.RotZ), fr5)
seg6=Segment( Joint("joint-6", Joint.RotZ), fr6)

# build the kinematic chain
map(irb6400_m2000.addSegment, segments )

# setting the joint limits on the manipulator
for i in range(6):
q_min[2+i]=joint_data[i][2]
q_max[2+i]=joint_data[i][3]

# set limit track
q_min[1] = track_offset_z; q_max[1]=track_offset_z
# 26m linear track
q_min[0] = 0.0; q_max[0]=26000.0

awkward difference in ChainIkSolverPos_NR vs ChainIkSolverPos_NR

Seems that my issue is similar to what Benjamin Bihler reports in this thread:
http://www.orocos.org/forum/orocos/orocos-users/using-kdl-inverse-kinema...

Perhaps we've stumbled upon a bug?

-jelle