Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

test-ik.l: add test check #1470 #1529

Merged
merged 4 commits into from
May 25, 2016
Merged

test-ik.l: add test check #1470 #1529

merged 4 commits into from
May 25, 2016

Conversation

k-okada
Copy link
Member

@k-okada k-okada commented May 24, 2016

this PR solves problem reported on #1470 (comment)

@k-okada
Copy link
Member Author

k-okada commented May 24, 2016

the reason #1470 (comment) could not solve ik from current posture is that the baxter.l uses weight to remove gripper joint, and if we use 7 dof link-list, it can solve ik, it seems manipulability value did not take into account weight value?

loop:   1
union-link-list: (right_upper_shoulder right_lower_shoulder right_upper_elbow right_lower_elbow right_upper_forearm right_l\
ower_forearm right_wrist right_gripper_vacuum_pad_base)
move-target: (#<cascaded-coords #X33f875b0 :rarm-end-coords  1165.63 -390.197 2.897 / 9.703e-07 -1.185e-06 7.515e-07>)
targe-coordst: (#<coordinates #X2ac2d758  1165.63 -390.197 -47.103 / 9.703e-07 -1.185e-06 7.515e-07>)
vel-pos :  0.000   0.000 -50.000
vel-rot :  0.000   0.000   0.000
vel-pos-norm :  50.000/  1.000
vel-rot-norm :   0.000/  0.017
collision-links : nil
parnet-links    : nil
valid-link-list : (right_lower_shoulder right_upper_elbow right_lower_elbow right_upper_forearm right_lower_forearm right_w\
rist right_gripper_vacuum_pad_base)
index-links     : nil
angle :   -5.4    55.9   117.1    72.5   -62.7    -7.7   -87.3    90.0
 min  :  -97.5  -123.0  -175.0    -2.9  -175.3   -90.0  -175.3   -90.5
 max  :   97.5    60.0   175.0   150.0   175.3   120.0   175.3    90.5
usrwei:  1.000   1.000   1.000   1.000   1.000   1.000   1.000   1.000 
addwei:  1.000   1.000   1.000   1.000   1.000   1.000   1.000   0.000 
ocost :100000000000000000000.000 100000000000000000000.000 100000000000000000000.000 100000000000000000000.000 100000000000\
000000000.000 100000000000000000000.000 100000000000000000000.000 100000000000000000000.000
cost  :  0.066 158.711   1.435   0.021   0.308   0.260   0.576 2593.337
weight:  1.000   1.000   1.000   1.000   1.000   1.000   1.000   0.000 
k     :  0.000 (manipulability:  0.274, gain:  0.001, limit:  0.100, len:8)
nspace:  0.002  -0.523  -0.256   0.000   0.073   0.027   0.142  -0.000
J     :  0.131  -0.253   0.107   0.067  -0.015  -0.005  -0.000  -0.115
         1.102   0.306  -0.734   0.444   0.106   0.493   0.110   0.000
        -0.000  -0.734   0.429   0.748  -0.056  -0.023  -0.000  -0.001
         0.000   0.771   0.357   0.120   0.991   0.000   1.000   0.000
         0.000   0.637  -0.432  -0.858   0.134   0.047   0.000   1.000
         1.000  -0.000  -0.828   0.499  -0.006   0.999  -0.000   0.000
d(JJt):  0.075
J#t   :  4.523   0.217   5.902  -3.484  -5.045   2.075   3.141   0.000
         0.591  -0.170  -1.493   0.727   1.419  -2.183  -0.829   0.000
        -3.044  -4.738  -7.209   1.445   9.790  -3.590  -3.649   0.000
         0.060   0.215   0.503  -0.059   0.086   0.387   0.576   0.000
        -2.142  -4.098  -6.055  -0.010   8.344  -2.819  -2.947   0.000
        -0.274   0.111   0.788  -0.350  -0.960   2.097   0.626   0.000
x     :  0.000   0.000  -0.050   0.000   0.000   0.000
J#x   :  8.722  13.573  20.652  -4.139 -28.046  10.284  10.453   0.000
Ny    : -0.059  -0.092  -0.159  -0.010  -0.113  -0.069   0.241   0.000
dav   :  8.663  13.481  20.493  -4.149 -28.160  10.216  10.694   0.000
dav^  :  8.663  13.481  20.493  -4.149 -28.160  10.216  10.694   0.000
loop:   2
union-link-list: (right_upper_shoulder right_lower_shoulder right_upper_elbow right_lower_elbow right_upper_forearm right_l\
ower_forearm right_wrist right_gripper_vacuum_pad_base)
move-target: (#<cascaded-coords #X33f875b0 :rarm-end-coords  1184.408 -449.192 9.898 / -0.01 -0.008 -0.127>)
targe-coordst: (#<coordinates #X2ac2d758  1165.63 -390.197 -47.103 / 9.703e-07 -1.185e-06 7.515e-07>)
vel-pos :-19.807  65.539 -48.933
vel-rot :  0.127   0.007   0.010
vel-pos-norm :  84.156/  1.000
vel-rot-norm :   0.128/  0.017
collision-links : nil
parnet-links    : nil
valid-link-list : (right_lower_shoulder right_upper_elbow right_lower_elbow right_upper_forearm right_lower_forearm right_w\
rist right_gripper_vacuum_pad_base)
index-links     : nil
angle :    3.3    60.0   137.6    68.3   -90.9     2.5   -76.6    90.0
 min  :  -97.5  -123.0  -175.0    -2.9  -175.3   -90.0  -175.3   -90.5
 max  :   97.5    60.0   175.0   150.0   175.3   120.0   175.3    90.5
usrwei:  1.000   1.000   1.000   1.000   1.000   1.000   1.000   1.000 
addwei:  1.000   1.000   1.000   1.000   1.000   1.000   1.000   0.000 
ocost :  0.066 158.711   1.435   0.021   0.308   0.260   0.576 2593.337
cost  :  0.039 2621.242   3.526   0.104   0.634   0.134   0.437 2593.337
weight:  1.000   0.000   0.221   0.906   0.612   1.000   1.000   0.000 
k     :  0.000 (manipulability:  0.290, gain:  0.001, limit:  0.100, len:8)
loop:   1
union-link-list: (right_upper_shoulder right_lower_shoulder right_upper_elbow right_lower_elbow right_upper_forearm right_l\
ower_forearm right_wrist)
move-target: (#<cascaded-coords #X33f875b0 :rarm-end-coords  1165.63 -390.197 2.897 / 9.703e-07 -1.185e-06 7.515e-07>)
targe-coordst: (#<coordinates #X2d88cd70  1165.63 -390.197 -47.103 / 9.703e-07 -1.185e-06 7.515e-07>)
vel-pos :  0.000   0.000 -50.000
vel-rot :  0.000   0.000   0.000
vel-pos-norm :  50.000/  1.000
vel-rot-norm :   0.000/  0.017
collision-links : nil
parnet-links    : nil
valid-link-list : (right_lower_shoulder right_upper_elbow right_lower_elbow right_upper_forearm right_lower_forearm right_w\
rist)
index-links     : nil
angle :   -5.4    55.9   117.1    72.5   -62.7    -7.7   -87.3
 min  :  -97.5  -123.0  -175.0    -2.9  -175.3   -90.0  -175.3
 max  :   97.5    60.0   175.0   150.0   175.3   120.0   175.3
usrwei:  1.000   1.000   1.000   1.000   1.000   1.000   1.000 
ocost :100000000000000000000.000 100000000000000000000.000 100000000000000000000.000 100000000000000000000.000 100000000000\
000000000.000 100000000000000000000.000 100000000000000000000.000
cost  :  0.066 158.711   1.435   0.021   0.308   0.260   0.576
weight:  1.000   1.000   1.000   1.000   1.000   1.000   1.000 
k     :  0.001 (manipulability:  0.021, gain:  0.001, limit:  0.100, len:7)
nspace:  0.002  -0.523  -0.256   0.000   0.073   0.027   0.142
J     :  0.131  -0.253   0.107   0.067  -0.015  -0.005  -0.000
         1.102   0.306  -0.734   0.444   0.106   0.493   0.110
        -0.000  -0.734   0.429   0.748  -0.056  -0.023  -0.000
         0.000   0.771   0.357   0.120   0.991   0.000   1.000
         0.000   0.637  -0.432  -0.858   0.134   0.047   0.000
         1.000  -0.000  -0.828   0.499  -0.006   0.999  -0.000
d(JJt):  0.000
J#t   :  3.987  -0.300   4.801  -3.192  -3.715   1.554   2.577
         0.719  -0.027  -1.204   0.658   1.064  -2.036  -0.681
        -2.282  -3.892  -5.555   1.062   7.736  -2.791  -2.807
         0.031   0.185   0.440  -0.043   0.163   0.355   0.544
        -1.520  -3.393  -4.695  -0.317   6.647  -2.161  -2.255
        -0.364   0.010   0.585  -0.301  -0.710   1.992   0.522
x     :  0.000   0.000  -0.050   0.000   0.000   0.000
J#x   :  6.537  11.149  15.914  -3.041 -22.163   7.996   8.041
Ny    : -0.072  -0.110  -0.190  -0.005  -0.072  -0.084   0.225
dav   :  6.465  11.038  15.724  -3.046 -22.235   7.913   8.266
dav^  :  6.465  11.038  15.724  -3.046 -22.235   7.913   8.266
loop:   2
union-link-list: (right_upper_shoulder right_lower_shoulder right_upper_elbow right_lower_elbow right_upper_forearm right_l\
ower_forearm right_wrist)
move-target: (#<cascaded-coords #X33f875b0 :rarm-end-coords  1179.025 -432.692 7.173 / -0.006 -0.013 -0.097>)
targe-coordst: (#<coordinates #X2d88cd70  1165.63 -390.197 -47.103 / 9.703e-07 -1.185e-06 7.515e-07>)
vel-pos :-14.363  47.448 -49.735
vel-rot :  0.097   0.013   0.007
vel-pos-norm :  70.222/  1.000
vel-rot-norm :   0.098/  0.017
collision-links : nil
parnet-links    : nil
valid-link-list : (right_lower_shoulder right_upper_elbow right_lower_elbow right_upper_forearm right_lower_forearm right_w\
rist)
index-links     : nil
angle :    1.1    60.0   132.8    69.4   -85.0     0.2   -79.1
 min  :  -97.5  -123.0  -175.0    -2.9  -175.3   -90.0  -175.3
 max  :   97.5    60.0   175.0   150.0   175.3   120.0   175.3
usrwei:  1.000   1.000   1.000   1.000   1.000   1.000   1.000 
ocost :  0.066 158.711   1.435   0.021   0.308   0.260   0.576
cost  :  0.013 2621.242   2.761   0.082   0.542   0.160   0.465
weight:  1.000   0.000   0.266   0.925   0.649   1.000   1.000 
k     :  0.001 (manipulability:  0.005, gain:  0.001, limit:  0.100, len:7)

@k-okada
Copy link
Member Author

k-okada commented May 24, 2016

euslisp/jskeus#380 may be the root problem

@k-okada
Copy link
Member Author

k-okada commented May 25, 2016

ed630a5 -> failed
592621c -> succeeded
2e9ce57 -> failed
2a25324 -> succeeded

@wkentaro wkentaro added this to the 1.0: APC2016 ver1.0 milestone May 25, 2016
@pazeshun
Copy link
Collaborator

I think test-ik.l added by this PR isn't robust to gripper change.
If this test fails when gripper is changed, I'll change this test.
+1

@wkentaro wkentaro merged commit f94657a into start-jsk:master May 25, 2016
@k-okada k-okada deleted the fix_1470 branch May 25, 2016 09:38
pazeshun added a commit to pazeshun/jsk_apc that referenced this pull request May 26, 2016
wkentaro added a commit that referenced this pull request May 27, 2016
[jsk_2016_01_baxter_apc] Revert a part of #1511 thanks to #1529
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants