From 2286f54e8e4226d24337cce3086d326d1b5e2f67 Mon Sep 17 00:00:00 2001 From: Steve Tonneau <stonneau@axle.laas.fr> Date: Wed, 17 May 2017 17:53:15 +0200 Subject: [PATCH] spiderman scenarios --- CMakeLists.txt | 64 ++++- data/meshes/siggraph_asia/grasp_spidey.stl | Bin 0 -> 51084 bytes data/meshes/siggraph_asia/plane_hole.stl | Bin 0 -> 5484 bytes data/meshes/siggraph_asia/scale_spidey.stl | Bin 0 -> 51084 bytes data/srdf/siggraph_asia/plane_hole.srdf | 3 + data/srdf/siggraph_asia/scale_spidey.srdf | 3 + data/urdf/siggraph_asia/plane_hole.urdf | 19 ++ data/urdf/siggraph_asia/scale_spidey.urdf | 19 ++ .../demos/siggraph_asia/bezier_traj.py | 12 +- .../demos/siggraph_asia/hrp2_model_no_arm.py | 72 ++++++ .../demos/siggraph_asia/plan_execute.py | 13 +- .../siggraph_asia/plane_hole_hrp2_interp.py | 57 +++++ .../siggraph_asia/plane_hole_hrp2_path.py | 109 +++++++++ .../siggraph_asia/spiderman/bezier_traj.py | 225 ++++++++++++++++++ .../demos/siggraph_asia/spiderman/log.txt | 26 ++ .../siggraph_asia/spiderman/plan_execute.py | 103 ++++++++ .../demos/siggraph_asia/spiderman/run.sh | 8 + .../demos/siggraph_asia/spiderman/rund.sh | 6 + .../spiderman/scale_hrp2_path.py | 117 +++++++++ .../spiderman/scale_spidey_interp.py | 106 +++++++++ .../spiderman/scale_spidey_path.py | 116 +++++++++ .../spiderman/spiderman_backJump_interp.py | 69 ++++++ .../spiderman/spiderman_backJump_path.py | 107 +++++++++ .../spiderman/spiderman_compute_DB.py | 121 ++++++++++ 24 files changed, 1358 insertions(+), 17 deletions(-) create mode 100644 data/meshes/siggraph_asia/grasp_spidey.stl create mode 100644 data/meshes/siggraph_asia/plane_hole.stl create mode 100644 data/meshes/siggraph_asia/scale_spidey.stl create mode 100644 data/srdf/siggraph_asia/plane_hole.srdf create mode 100644 data/srdf/siggraph_asia/scale_spidey.srdf create mode 100644 data/urdf/siggraph_asia/plane_hole.urdf create mode 100644 data/urdf/siggraph_asia/scale_spidey.urdf create mode 100644 script/scenarios/demos/siggraph_asia/hrp2_model_no_arm.py create mode 100644 script/scenarios/demos/siggraph_asia/plane_hole_hrp2_interp.py create mode 100644 script/scenarios/demos/siggraph_asia/plane_hole_hrp2_path.py create mode 100644 script/scenarios/demos/siggraph_asia/spiderman/bezier_traj.py create mode 100644 script/scenarios/demos/siggraph_asia/spiderman/log.txt create mode 100644 script/scenarios/demos/siggraph_asia/spiderman/plan_execute.py create mode 100755 script/scenarios/demos/siggraph_asia/spiderman/run.sh create mode 100755 script/scenarios/demos/siggraph_asia/spiderman/rund.sh create mode 100644 script/scenarios/demos/siggraph_asia/spiderman/scale_hrp2_path.py create mode 100644 script/scenarios/demos/siggraph_asia/spiderman/scale_spidey_interp.py create mode 100644 script/scenarios/demos/siggraph_asia/spiderman/scale_spidey_path.py create mode 100644 script/scenarios/demos/siggraph_asia/spiderman/spiderman_backJump_interp.py create mode 100644 script/scenarios/demos/siggraph_asia/spiderman/spiderman_backJump_path.py create mode 100644 script/scenarios/demos/siggraph_asia/spiderman/spiderman_compute_DB.py diff --git a/CMakeLists.txt b/CMakeLists.txt index dede5ec..cca37dc 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -92,9 +92,18 @@ install(FILES data/urdf/darpa.urdf data/urdf/car.urdf data/urdf/polaris.urdf - data/urdf/siggraph_asia/down.urdf - data/urdf/siggraph_asia/scale.urdf - data/urdf/siggraph_asia/grasp.urdf + data/urdf/siggraph_asia/down.urdf + data/urdf/siggraph_asia/scale.urdf + data/urdf/siggraph_asia/scale_spidey.urdf + data/urdf/siggraph_asia/grasp.urdf + data/urdf/siggraph_asia/plane_hole.urdf + data/spiderman/urdf/SpidermanLFootSphere.urdf + data/spiderman/urdf/SpidermanLHandSphere.urdf + data/spiderman/urdf/SpidermanRFootSphere.urdf + data/spiderman/urdf/SpidermanRHandSphere.urdf + data/spiderman/urdf/spiderman_trunk.urdf + data/spiderman/urdf/spiderman.urdf + #~ data/urdf/scene2.urdf DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/urdf ) @@ -126,9 +135,18 @@ install(FILES data/srdf/darpa.srdf data/srdf/car.srdf data/srdf/polaris.srdf - data/srdf/siggraph_asia/down.srdf - data/srdf/siggraph_asia/scale.srdf - data/srdf/siggraph_asia/grasp.srdf + data/srdf/siggraph_asia/down.srdf + data/srdf/siggraph_asia/scale.srdf + data/srdf/siggraph_asia/scale_spidey.srdf + data/srdf/siggraph_asia/grasp.srdf + data/srdf/siggraph_asia/plane_hole.srdf + data/spiderman/srdf/SpidermanLFootSphere.srdf + data/spiderman/srdf/SpidermanLHandSphere.srdf + data/spiderman/srdf/SpidermanRFootSphere.srdf + data/spiderman/srdf/SpidermanRHandSphere.srdf + data/spiderman/srdf/spiderman.srdf + data/spiderman/srdf/spiderman_trunk.srdf + #~ data/srdf/scene2.srdf DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/srdf ) @@ -168,9 +186,43 @@ install(FILES data/meshes/polaris_reduced.stl data/meshes/siggraph_asia/down.stl data/meshes/siggraph_asia/scale.stl + data/meshes/siggraph_asia/scale_spidey.stl data/meshes/siggraph_asia/grasp.stl + data/meshes/siggraph_asia/plane_hole.stl + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/meshes ) + + +install(FILES + data/spiderman/meshes/spiderman-LFoot.stl + data/spiderman/meshes/spiderman-LFootToe.stl + data/spiderman/meshes/spiderman-LForearm.stl + data/spiderman/meshes/spiderman-LHand.stl + data/spiderman/meshes/spiderman-LHumerus.stl + data/spiderman/meshes/spiderman-LShank.stl + data/spiderman/meshes/spiderman-LThigh.stl + data/spiderman/meshes/spiderman-pelvis_box.stl + data/spiderman/meshes/spiderman-pelvis.stl + data/spiderman/meshes/spiderman-RFoot.stl + data/spiderman/meshes/spiderman-RFootToe.stl + data/spiderman/meshes/spiderman-RForearm.stl + data/spiderman/meshes/spiderman-RHand.stl + data/spiderman/meshes/spiderman-RHumerus.stl + data/spiderman/meshes/spiderman-RShank.stl + data/spiderman/meshes/spiderman-RThigh.stl + data/spiderman/meshes/spiderman-skull_box.stl + data/spiderman/meshes/spiderman-skull.stl + data/spiderman/meshes/spiderman-thorax_box.stl + data/spiderman/meshes/spiderman-thorax.stl + data/spiderman/meshes/lfoot_rom.stl + data/spiderman/meshes/lhand_rom.stl + data/spiderman/meshes/rfoot_rom.stl + data/spiderman/meshes/rhand_rom.stl + + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/meshes/spiderman + ) + install(FILES data/meshes/hyq/hyq_all.stl data/meshes/hyq/hyq_trunk.stl diff --git a/data/meshes/siggraph_asia/grasp_spidey.stl b/data/meshes/siggraph_asia/grasp_spidey.stl new file mode 100644 index 0000000000000000000000000000000000000000..a7cc366239d9da8d5e7722469520e1f69efde880 GIT binary patch literal 51084 zcmb81d(?Ghb=|+j;ssKzCMd>BKoJ!pQMss5Iq!#(4mCmtrqN=}FfD58B^otGiAjzj z+7K^+prWlw5$|`Di;Y1JiXz&m(K0Yz8?4uAqa$LCwU&Orwcg);=GmO{jnVzbagM#` zTyw5<p0m$>InU=w&wa+zpZV-3oPOvNpZWBs9eUzZpYWTfKjE48y6@5VJMPeXJnOgr z&7t?c=brzs<Nw@5`f>rf?K_qy?AdeZ&YnHDI$r#~8*aG#mhb=Eiu2%B+;GDml)@{i z0DFEY_Uu{it1)?8amBt`yB=5U+4J#BcNK-<akL_@h*J%2{;OYo`(sd9mn*5*#nFd~ zypo+~rAoB;{Kcod3*;5DizC(Kv0Oaii7!Y+UC|@vb_JEFyl2lb$9(aUeSIvf8y-6` z-7ALTxOGLc5>JZd>S=E{<f1+Mjt%oEmJ`7b-g5QVFZ<-XL3u?StEAr9R`AO4?bCi| zarmd6w>soSUs#B*z4Ge9*Sz)Y6}XwMtG|5upH2#~3M#4Sb&D1jweS$bO7-MXE0H8B z#46TPwQjk}>{&Pcn!Br*+_Q7B-h1}!>$(!5GKs95+j=TzWhy&Q#h8_BJj|}bB%XJ= zBbgnVDi!Ogs82ukK`j$*pDyXr!z6P*s`p(1bh9h3I^no8E?E8e_^VD3|J`GMv+x-Y zx^xAG$I&b0z^@&+P$5>qc@<+_!J-x(Vpyqe2a}ORg;>QrRV7<x_N<$JdX!=zD?1nK z-L=)3M3z(Vyq$M_UQK1^sn|X%S!Pf5nn$hpWSK<8_E~wwg!`Rt&B~d~=jQq9dio4r zdFGjmH~iL{SI;^6Eer86Pklw<Zyj^l3XFoISISL)>AXoHRzW2dV_m_b79L_)scr{8 zO(2q}5UZG{g1=m4_N<$JFg=!&dv-3?d)yV!nM793Z9SEDAXC|SD#om2<6(9cCh@$} zh1+)rJ2X`))>ENzR$ejTey2OVYo^LR^y}JXvG3)de)cIRa7TW|kq<aQ{LT;l?SsJF zMZt1=rJVcy4^0ZO3M#1>>k1aN@DRgF_2g0ON_SJ4B-JYT-{mT^XWgxeg)BXC3a0Ja zI?Yqf6?R^#`ZSu#&Qq~{R<g{V>NSs=RkAXn=Tp(26Iom_A$Y5zX5~y^nb1lkT%Xlt zSG{a;@0%a7`t_gsUkmXaAO7XS|M?}4T!Ecyuaq19_<~6xRzW2dV_m_b79L_)sh&J) zRwPj&RxwZ2{bcs6n|^wfVsg*U#d>#bbtaLObDO8??oDOqsn|X%S!PeQ(;dl@l?gqc zidM<uiV62S-RWJ+Bu-(>%5NK7sC%!=-oARmXMbWx{Kwz@PWe6k_pexi;c<+0rGo5W z72^6_OgdQ9!b6NA)$QQDog^y6D(0yw*($SV-SpF=6q9>)F4ntit22o#r{MV;&&pJG zo{BLmCyS5SRhY!{YaaC(v_n&+;>NS$z0bTR+&*2trPISCbHDXxhMWBK1M084U-|mE z3-PV*wk*t@5A0kU{mFTcpA=#h+#g$!&kV4rg@+hcswa<{6-iWxRm@YNT&^;E)=fV> zN-?=-=VHCPwmOr@qFeDiRnN*)uuP?5%qrJavdo_9o^B`V=c{C8LeHn7-+NhHG2!;< z@=jVSli0`RS@GQVn#10F`J?{iih5QD|Ff&#Uij@t{-CgP?OE}hs6wnlb-f?cdW1zS zJj5tc-5z|JK%`P3RxwXiUiI9rd)7_A_UPAsZnuy56!h-e>P(We60fK7Q<Zg1rNXr3 zu{JAHnccaiVkApeCiFaWvx8R2n!jsX71O(xN$g|H%6AW!vtIhTy8Ar;Nw?Y&pZ1~y z3bPWy@Hl#1ef*U7P71LKK7*}rvglw@3lA}@RKw%w&mc)uh*iu}wJNh`-SjJi-IwJ; zR(3AdyKAd6i7dJm&r|iROa*I`U(d?P;*%`1r&`5GmaI(Z`Bbz@7FSFN-m0isITKj( z&Pg~Df$n#ocP>u-<|{A1=8~g!#P7N0u)>f3hp%1^hR4yfI^%mEm=t0aR8rAwbg-y} zhZt6>;c@i3B8dvIig~J5W%jI_er2%xvRuf@&c%9nZFMG*m2;b?>h4Wt=c(8}D_Lew zwbLERl9dTPpNdw=;))6PJKdU<GnvoL^CJ<6_4?@--DUNY2i~UEF8I28+`RB(4tjWD zcpN<|)~gD!3e|%Rf<-Mn#3)h?k7L}gRFKdlscwG1E?4$3ue()IpF#Uj?G*GLi9jZi zm1+}q9%q$x?Kah<MKL~u$uhfh%juS?o*9yr2|cd|3XYzYc}?itJm1`Y?R&d3$%N_G zwbgy)yuVqT|Ih;-{DbG-e@A@nc}Exi#tVM<esFXBW;^1vuS^QD3M#1>vw}q}JjAe4 zJ$cluNTNclVm(#smaEL3b<?l8yNZRZ>|Crj++OJ*lgP@st*3HUrn2)?Y@d}Zv!~kW zj=#Q=l?gpR6!btpvbbWx{Z6-L<xJ*t^ZZDJ3w6JAhoe^a`sGD=fDd}gafMGm|J1_p zN>$H))Kwu?p?a`U!lD))Vic){$I<U1sZ@wntfx|CAF@o6e$Cxg)U517wNua=?)tj& z$|eQgU45UbW|b_v)x(74QEX7M%<kM$G2X>w;b%h6XR21o;))5K+l{BoXT(~W#6I+^ zKI*Oj;!ei*`7@t*v-<7>pMT(w7M$ms6AX`Id=IMNo|p>pV1r;$3lA}MQw@(}d=IL~ zB&lwGzxKUd_pG~BF}Y{wV!cNqkV#}Y1<&7jR$P%~s#L2O_x5C&9fjvrjAY3&iHi9< z*eY4nG9lPX=~0U5igoSDN}L~wKs>iS=Ddqf_=or2sh;7$pS<>`3%~M?k0=ap+<|y* zQz2HN8vd9SENbB)Mv-b19KEhcr9!M?J(Vi^kY$qeYwoV1o<;3LwNuc0+!aunL{_Tj zsk-~DYqzN;?U*bc$uhfhvnO~XS+X*r=i8$-ye?O=xMD)*Ht(YpH7jS539UrJuFWgQ zC6BzWK2Z<(+%NBl@AAVF3$xn6@J9DPxYhS3g;)jaSjAXZu&9NH7*?t$kGhkRM1@$z zdaBkfSD8KQreAY+6$@F}xma(w<9pB~vglU4p33JdQ^DHgw|Q39HG8U6jCGZ)Oz8Qc z*zLS#WnL5Rce*tzXEN`@^Xs!>pTr%{Ie7IKum3{rjRBwiA75Jdf`cDixbt`iVxNQx zu?p4YF@1l+q81)v6sev(YF&{^g;>QrRrg~bvP_bGdUQJ7vvaZDU0a<=WH|-T<1M#8 zRi?7@RG6^SsLNDlPxYEd%_><YQL%kiUNNC_^SpUFU3z4~^ebj10zLGGgBAxr<OQoQ z?77WC{I-9*<^=F*2fShhhR4yf`Y&f5GbzL>sH9@tuV7IN4>7D%w}W>F-A!eZRI8|D ztIVEtw<;>hyz}$}cWs^KsZwo1x!t{~>^v3QXC=$*sdl;}S+X*r=Tp%tSzIxp@5j84 zQcUk!CIMRsJQ9Jpa*x}deEEw%{*YpU|H;GdSokhKb7^6C9AjOnAbTprgAIa3Ej+|{ zq#7Paf9sG+g;>QrRjcenmPyjD40d0ZlY4e9*1Kz~Gl?vx;CZ~|j&&u=Zd0vd{WF*f zlc-iPlG&kkQ?Y$kUYXC$^Y&3b)4PU;N#=ed5s2R%k9_wLtCPNYYW)TYzT)(w3SW5K z$%Wx@bocxQsY0wm^<aZwQ40?-id4hn=ygRZ6=D_hRIRcPStd!pGT43TU%l-^wNuc$ zYpXMftW?ia^{le4-KLtf<uR?tWSQN$*^_yCR>{hQp4VfjWO2oW&TZaDr?XZjv5)Pu zy8e=%zx=7Eo?RZ`QxAP!;hUfShQd>#>K+djVil@8jXGG=!b6NA)pEzWQbFe?Nwtc8 zf`z4f*4?U@+_Q7B-qpuSCzHr>3ZADYxno_)GF7TojQdrx%#OnIDn_zonM8$iGgYf( zQ45@N+o+h{HS5}wl{h~Vfj)lK&+hOm;%(1Adq@1jcfGhUzchm3adh|JdDG#OLac&H zD#ol}Q40?-tW>vy_bZa95UZG{s${Foo^{htk5VjTW#?kOyS6%$$jZ6RQ+4;Ivh!4I zpOq}Lr`qX`WXZ~eo=-)qWO2oW`<-sh%9+gP=K1j#DlT6=`&;#|AohId5j)~9etB<U zcEp3>jsMPY<fCqw6k-+Z_-}=OX`_TiEj+}qQVnk;BZ&&JiuF{gGJDodzp|(o(#gus z#d?oK$V?)OZpG`V?A}zcHu-Iym37UY>Q<0upGVzEla&cQKNP6=<jUfT3Bg+xH7jQV z%Y;@UVb|uB<9qME^A5Y<@Aa`Wcf|L<==Tb<BOYADeJ}kPJowyuObW3IDybOvD_GRR zLkug`lSj>pBr3!z=BZFFSD8KQrk@_ASjfuG#d>#bbtaLObDO8??oDOqsn|X%S!PeQ z(;dl@l?gqcidM<uiV62S-I|p%na|DhW2NKrOOO3b?WVcvPfyqpzu}$77Um8IhR4yf zI_pl~niOIc+`(JnCl(znYT+S<m1=k#{d`3d6=D_hRISSFSvUR4VE1LYkd>W__3qm0 zOd^YJ#q(4>D^tPR<kz!uviKy+?5S2Uk|iq>dOj8X-pk^O3Bg+xH7jQVYu-5tM<UQO z9(DK*`}E)Z6X)%SZ+GiIE6k2~Fg%W))j7u=Jt@R0sHCFV=wML`4>7D%!y7A}Br3!z z=BdyvSD8KQrXNg?<w90=F4h}%uXK<}WaZq}Q~9Yfm7S+z`>bS{J=IQkBuiE%^n5B> zC5tO2-0yU2R?cKTH_wkmAnLM%|HP;Khw=cw=ZserX4gF!9>-W$D)2~!c(6gRsD+1^ zx~Yc8(eEOuRESl~Q?<%IWSJ!W%3$}U*Oh&!b_#lTZFMG*mFjt_o>kVh+f+N<_0OPn z&F<Xn$vi!)WMx9n>(MHn%4BiHgwAc=M}5|7T{)9^AD&;I)qg$qp!)0Xqu+i0j`+>D zdRAfXeBh~%`djk)gAbk*VinvURg77|q81)vSgD>o>iLQ!D#R-0sk)!co^{htk5VjT zW#?kOyS6%$$f8^EJXLpZDp;HRHqXksW>2+>kt|u6(DSM2Zv<IfF(G)XqGshxV42WL zBpiuAJh!nQ|M1tIRnKtXmtXith1n4ghS%$s|K+(&g;<4Zcw=3`q81)v6sblrz6VLA zLabsvl`8v?Ws>wOi+bUEO84wstT*KGJ!leHPQmkdS9$(ctIwdR>^v1FERSM?GL_j= zz2;G$!DN|4#f@i0KeDK0Lg%(oQL}O;nb1o3RUefIbnT@_*Xld@zOUU8zkly*3bR7N z@Hl#<{P4W{PYSUL*0GAQu3%9M4>7D%w*z-+5J^;sRm@YtU#>EH)=fW{9?ONS>|Crj z?6Iy)B8zUt>#1B<rh>J}Z}Y6IYxY#D7|D{A2|b^RR>|Uu3Bg+xH7jQV%Y;@U;Yb8} z$IXx3VPD1>|LR>k;&1-OTMM%T0t|25um0wn51tfa6;x6&))g#j;UR{V>h|zmB#8>K ziuF{jTdp#D)=fV>_}}G1R(3AdyO`5w&?K^QZu3;#y{YUx729Ve%j~Iky5ruStW4<n zq3Hg5R^~O~ey3ZrawhY+d47FXtT^`LpL6B~wRXXK&i(Vk?34$09^MNO>s5tVg=%<X zUBRLj9%2-!MlohZDivZC^Hk{iex-ZXO+T0(eZR7g`4seqy?(#)$|l8_Ro<`kFx7n0 z<x!IbCClv2&HmtVbh2bQD;3*k<rVwb?{w>aW#^eN{YE0t0S`K9hkg17{naHq;@|z) zg@xG>4~EClE9Gu?I%QIbRZvOASXZ#9g@+hcs@uWuL6WEttC**%WUI`cb<?js`gOUG zm7R<A?%L{1A}i;%p2~G)Dmzcb_F2g?d#au8NS3Tj==oH%N)}g4xZmm4tenYwZk`{B zK-6VF{u>Yf%klspeC)-A*%1$hH@*j{t3s?oHT?B;MJ+r~SU1%u#{G&^D#UoCx)uGp ztaYV(*4?V8S=q;Y3VKt0+^<ZMvl81==gD=YhpAMUwmhc$RkF<P+)^=Sm8?wY`SA{R zww{%F?R>w}tywvfOqhPv$ErR037PNnkKU)h`@r|#`>OgL<eL*Lw^s`HK^0;Zs>@@V z6)bAuAx4qv_V9ki{Z)ln#XMDc)pNV<SvURcqtnUC&c%9nZFMG*<rF+WX63r#imXk3 zD#m9pS!Q=`_Gg~)J!oE&sMtO$ub6PZ)2;78Ju+eXt<Q?*HumG6b=sTjSsna?fA_k= z?34$0AI^&BHWgwOs>@?qSFosshZsewCy!e3q*5VPv7V}R{Vb|`)=j_W?keh8)IR1@ z&>QZ!UzsFlC0<YEtg^1DRG79r)@EfYvpcs`jQdrxGNI?kJBSmXTv_vXZL6YY<xF6i z&`Kn%KI+{A{m)lEvOZDo{?=+oeAtiPSC|zFhR4yLs#`wy(UU@~f=`r+@fn0gEj+}q zQr!-|izHDYRxwXi$yS*?>!zO`rC7+y&c%9nZFMG*MYrO4s_x!Yur~Q^o|SdYo@x~% zS+X*r=Tp%tSzIw8c&nmj<xF6i&`Km6D;*bhI<SNPqH|8JJrm$_E_`TV_RxdjarCU% zC!s>DLUnmepFvpE!b6NA)$PEi2}CLtViogL@O$rv?pZheV0tWT?}vTNr=U0NalbN2 z&Pu$V%KKH;HI)j}mdDzxOl5ZGmWq)qS((uD`3|;9*8E-Ds;F5x6Idp+5(!5l&`18; z4fU@ee)abry(2#EHIFRJ9(pi5j$T&>eCifE?CeJ&R>64{<9-E;S}LrY>UQv5B#8<! zb*-ewP-XV4yH&A}m7R<AuCAwhyGdj@1<z-y?%q^(o{H_Wl4bT(uX$9mWSK;TlXgzs zk1T4L5NxINC`HZ6nat<r`5VuQefnp9_urNW`0=+otuTA&!6-P!x>A8hD#U{gf<-Mn z#MDhSJdVCQ(5(uwig~J5!O}hJre7KCzAS52_MzG-=-su|nM78q=c&fJl4Yt?JKgoq zU@A<aTE$3aht^HSJXNdggIadJ-|5z@vaSiOg!f1U;+I4A<3HoQPpaP_!KYmNxWep+ z2gBp&?)lwOg;<5^!3M#i79L_0sfNeV>xxt=#46^g`g`3zWSJ!W+JRTTr*zNG#d^aX z--9NR<rF-RHwuoPm8tAJ6($^PP^L0_s@FW~ew8efsJQX0=tmZ{Oz7M;Dr#2FBokT* zzv`nBfw;mh_+LHZcgq8O>`A{>m_77hc;ktQx+=sfRKp*iL0HtnLyRKTC^*KtQb9tK zq`LY2+OyI<>uy!ltn6bx1-(ZikV$e@ViR^AyU)6&QeoQiSg1>u*_~S|`qP9eS((uD z;~i{|o|Sn`==<S$^YFjRnw2xjgy~nzX<eQD-G5)dA|86?_jbhR{Mp|Z=9fk=3XWbW zhh6uQNg-Cj?~y9Tx`IV5JjAe4-43oRlBf`?n5U{_tIVEt(@&35EM#TpV!gYzI+Mtv zTk$+qcW)|KoBTG<%DQGxwTh7}S((uDsc4lfu9y(KRZ+8YCa_FsB@&KApsT+8<Q;aw zAN1j?cf@C0b7f(6%7fu?^sK&q<+CS+SOt|-jCBQzT6l<IrMewlS0qs(RxwXi$yS*? z>!zO`rC7+y&c%9nZFMG*m2;b?>h4Wt=c(8}D_LewwbLERl9dTPpNdw=;))6PJKdU< zGnvoL^CJ=Hu3tN={uRXi-tn~^@tZEYt}r{|!SFbGRu^CUvPmIU!H$0wV_m_b79L_) zscr|?6-iWxRm@XWvQ=i!y6LA!DHgJ_bFtoCTb)T{(XDu%s=GH8tWAEKXJuWpr&`5G zmaI(Z`Bbz@7FSFN-m0isITKhWv=RwNBGC6g^7y)|{r!<2+z~(S7vEo)J0BPxN6+ez zw>)`Lh*fZZR58{SENbB)hL!4ea9xo^g;>QrRV7<x_N<$JdX!=zD?1nK-L=)3L>AqO z=c&4TQ^DHgw|Q39HG8U6jAY5mgq}}Dt7LJ-gy5};nw2wwWkM^Fa3lg<cj-&&UqM{- zl^^bi54-;Q!t96#!{g{#J@ZZHObW3IcKoXt>k1aN@DRgFbvwAONTNclVxFp!tulMo zO+P(Kv5=LWi}mi>>P#YwZpHId-My(`ZSvbZE9;s))hb4^WMx9nr=nG|xMD)^Rz=Oq znZPokl}I=efw;nc{F6`qae06*d)z-3W=A|29>-W$D)2~!c(6gRsD+1^x~Yc8(SHw; zN`+X(JXNdgLzYR>uMBoymNhH;Q0)}-?%L{1A}iJNRAXJqvfETU-Sy94DomnU#Ykp{ z)=kAcRjcfST6XT-HY#dXS=WSC!h0kFoqP9X-PNA)*z0!0UwZNv3UlWJ!{g}g?|R4! zCxuuA_eT|DR<NjrhZt6>+rf235*1<<^Hh~=mD#gy`sq=Mg{<sctasN|XA)U-E1sw7 z?o9=2li%i9S=a2TRxy$#D-(J?6|IuR6%&HDDr#2F1eOV{M8c5>#FH00_<!M#zFp67 z;Qw^)*9)^#9t@A8XT@`y3b6{+gAIa3Ej+|1QVoxz?^mQ!AyzR@)&C{OK4h6B{n~+7 z{=2B|*|}J6xZ}TznnadU@I2lqICejSG2KmmD#m9pS!Q=`_S6n0OO{Dg+;~=~WZ@3B zu9ZwR`P8hONhY)sez3=^UjB`9YW2PSz@OYJzWVSRcEGGqFba<D{)o@Ma#Dy@u#Q!X zS;3+f9%5LjZU>X;ZYq<cT1Bs`%${|(Di*TzAiLPK)%En>`sS(T3Og^=f>%@7c`CNg zN|xDEz2;HLl9dTPpNj5B7FSFN-m0isITKhWv=RxsHm@AZb6#G%9!|XTE%u84_Zx0n zn4J;eX1cC!{fDof6k-+ZpHMN@6)bAuA%>Oe$)jdP5*1<<^HkNvDzj(Z^wXmh3t8E@ zSnsZ_&LpzvRy<GD-J1&5Ccn+IvaZ=vtzslgRwnd(Dq1CrD<%YQRn)AU2`m#@iG(8& zh!w|v{6}8Y_bc#CAGoLPUF?(x!{ZqDD;2EWREP%~1dCdDh^d=ucpQBvC6x-Xig~JW zztTPHre8bo%J-nG>|Crj-1U3ASLSn@r|MZHYm=YT9iPEunccbBAE`JxS+bm!ig~Ir zE3cSvztgQ**?A^RzmW)Z)KP!l{|e%ipV}+_;I+3X%#L_4JdW=EvO8QbDa0z+@vmac z3Rdl|-{&EQmFjkIRwPj&RxwXi$yS*?>!zO`rC7*1C^{GG-L=)3L{|O#hF$eMRd;VH z6r21u&&s-HPqm7XELoY*^QmZ+EUuUkyj4-Nawf1$XeAPkL?EuPAOEvAxn+5P&wlYi zh1n?&hQ~41l?pskAs%cHENbB)rf#a?ar9@9R4T+O=BZj`AF@o6er2%xvaDIzhia#w zch^>D5?QI9ryA=@mffb>>8^hUQ(+R-Dn>Fpv~DWqsaj<p)UtEuwoy^D%DN`B65b;b zh&vhImQOygzx%)sIs8ZUJjXXG7#>G=&wWsZScU4r2En2h9%2-!hQ~3!2UU>JB&lvb zulv5$R`xNkyH!#5cKcB66!fP0`uCt$HYsjAt7O@&9@}SSDziJcRE%WF!q0@B&s43F z#T64eHzy6#V_CDxx+b&|31N>}@#MuW_>cX?0rd<Ae!&qpDa=lJ@Td>sxlM&wg=%=? zGYE@Xc!*J?8U;ruBb5rVig~J5*@rBXq+c2AzAWom)IL-@1--krI+Mss^*mK~pLOjv z)ub(t`s)#tEVDZ|dz$jp-#E$2gr3)9sAO@)gwAc=2dbWxGs%QjB4IHr5$OEKyteK> zzxJeC?-k$nJGU&%3I)UC=vm$SVQ-uiVil}o6=Pk&q81)vSgCFY*A+=rh*iu}RkBrP z&${WSM=2JvvU9QCU0a<=WYMj7o~pYy6|7Bun`dQRv!`0cNS3Tj==oH%N)}g42;Qow zSveC}CbSX>M<NjWB-jQ2)uTREdnUlY^1u%lW~V$D9!JlLeG)3fDpU_P2o|;Q5Ti&n zJdVC!kxGSF#XMDi588(;lcZle@XFtVx@YHNz2S~~yGdj@1<&J+f}>|;Dmzbw2?raL zsmz}0HIKSGB+Dc!Zagdckwq;NI=79Anw2xjgjT|@`k3xl#~=9H^{*h_``S<Ji0}69 zj}~S}JQxK>&+5_N`u#~ER>6*c70pHmi&}VyVWk=#N56|CQ6W|_Pt~f-o^{i&40d0Z z3t8E@SnsZ_&LpzvRy<GD-J1&5Ccn+IvaZ=vtzslgRwnd(D*7`hiz_AsZ&lQ+oCz!w zT8V@s5r`}7f`7#4uPG1kU;U3y7G|eB7#_!1S1RyGg?O+*u&9NHn7XNk$1&EG3KE(m z)y?nM<;p(hb+;;NR`#LVDd;^CflMMR)h6sb&MNELZK|E_`e)F(W_NBm-H|L=nb7lk zOv!3i<~5;n^StcxsaZLbc^{r1i9q~v$PWH1FTb{ag9P9A6Q3%~PI)jqj_#h{9aV@` zs2*$(ENbB)Mv-cG9KEhcr9!M?o~l*$A<HD`R|dN;%la+VK2$pey}PzLlgLW-JXOys z>)LIqNn0KZJ(6X1=VniGdsfNHgr3)9sAO@)gwAc=N2jw^Cb5t0vtmE~@z43Y@&Ld7 zg`Y3XPI>T@sJh2Pg;<5^PNNPMweS$5NVVLtu2j&uNm8w%ylOv#?pb%MqSlpt;E`DG zuC0?va#ms!${p*<x~5WL+VWUiSE(?G>b3Wyo@VUOx~Z6_>VE8F{;pXmJvyCN@G!~T zuWR$langO>U%w(Ab;`Z=ivRnyM;7LnMsPE|Uw!7V4^9fP3Vx4NG4AcKsD+0ZR;nkD zniWY@h*iu}^)o|e&${WSM?bgA%Fe}lqv(|mGKnm@70*+3_ojli$#3(ltZVjEs~E|W zl?gqcidM<uiV4A66$`IqlI$Ej5`k|2p10P&f;jZMx7#cJ%<mjrm>uz8cpN>ew_Nb9 zNg-Cjj(-(nUBRLj9%5LjZU^5*lBf`?n5XJ>mD#gy`svZ@N>+9**1Ni{l@2nAEV>oX zQ+4;Ig0;zS^Q^3E_Ef7F$&!@`J)ep(EAyIgztde<E0bjB;E@RQw@0jc7yMU_*em|d zQw}f8PI)jqj-J(%Z}*`|Ay&bDdKF_`!Kz*N`#i+3Qr!-&E0U-XtC**%WUI`cb<<Ce zQY>WMFFF_N-L=)3L{|OlfnD`HRd;VH6r21u&&s-HPqm7XELoY*^QmZ+EUuUkyj4-N zawf1$XeAPkM4$^_|AzWjyUpu<X0P~TN8Y9|_jWKmj-J(tuXyXE5Ub!0u41e!Sk%Hp z3@g>`;JPA-3bBfLs{RaS_N<$Jdi4EDR(3AdySkq4S0<4~x8ixK?%q_eHu-Iym37UY zY84|{vNECPQ_(6}TrnYdt774mOp=|0M<UR9KlniHg1`O`?!8z1wwoPYn4R)qcpN>e zyMN=VNg-CjetH#SUBRLj9%5LjZU@&DNmPhc%v1Hc%IsM;{q*Q{B`Z4@>s?(>>&hgu z=vF*W)!my4)+WErv$C$)Q>|hoOI9ZId@5Qciz_AsZ&fV3l1Z|2@JIxrF1z4AaO{1{ z1N^+pexWcs<-zbc#=260Un<0d4T422JjB#ZH9U@fN+y*Gv5I-BR@sLvlcZl6?7l2( zR`#LVDd^p`)tN+As^_W3x{_tLsdl>SpTSg^M74^M%nq%aig~J5*$1`k+_`O3)U2|u z39W?pNCbM=Z(LH}YNtN%@V(*#uRN?U_jWKmj_&@mk9psu5Ub!0u42pz7PasY!%B5K zxUNW|Labt*s*<fTd)7@qJxZ~Vm7R<A?%L{1B8zUt^HklvsbFpL+dM1lnmyGjMzUmO zLeHn7RkFBZLhx2a&B~d;GNF}7I1+()@?zioMW4K9J;Q;Y{OG$EW~V$D9!JlL=Qb5$ z6{-gt1dCdDh*6{(9!KA=NTouoVxFp1_94q8=~o83FUxuswGY)!LGP}u&Lpx@Jx|rM z%DQ%&YSNa+LXTvb-MQJ5+@4jkGNI@7Xcc>kWO2oW&TZaDKQmY>li0`RSv~xoAF0*% z&tG-iUh)6^xnl~mLcvoX)&1vg|JRd3tb%o{V%)D_Q40?-tW-}P^)y2g6=D_hR4A9L z%${}APmfY8WM$`Ky}PzLlgOf5@jO*`Zz@=u{5H?Zx@J$cijgc?nb7m8Xq7Ckm=L^G zQL}O;uuNzr5{^Wm<3Ih;+V$|ow>@aD_~pm^VqtbhfZ=iUtUmI=PfQB23ieN^80!ia zweS$bN_9JUzaohWv5I-BO18@ESvURkD8)inb}rVtYpXMfEV>oXQ+4;Ig0;zS^Q^3E z_Ef7F$&!@`J)eqJ$>NF$!CMtID`x`BgjOQqNCaZVeR|)&mH6h)@wIlr=U?6Hn4R)q zcpN<|)~gD!3e|%Rf<-Mn#3)h?kE8GHq*5VPF;CSh`;cXl^ecnimt}nh?L)Ow(7S7^ zGl{HJ&r|iRvaa2xnzZFHeGewf?9R=e%+s?<Rwnek9z!LID<*Vq^FBJAwK9o)Y@XG1 zPx*B1f`8)|7JJ3NcKU-0vr`^CC93Y9`L91SDa0z+Pp@L!uV7IN4>7D%PagF>ND>ud z74uZp`6{z#-SpF=6bo6|xmfS6t<EH}=vF*W)!my4)+WErv$C$)Q>|hoOI9ZId@5Qc ziz_AsZ&lQ+oCz!wT8V@s5r`}7f`8UId&>iS)a`qXu~QxlkE3TrT@_*#ss|eci&}Vy zQKT9kM}G!Mr9!M?o~l*$A<HD`R|dN;`~LqKq7T(hLGP}u&Lpy&g6Hv;JJyw~O@1oY zKZB_-iE0%inH`!c729X!6+3rsp0|(ksaa)R6WTf6BN2%EAm5e;ysGbs;LCpQK6QWO z8x;(Xqr2yxs6wnl^<aZwQ40?-id4hn7~g{`NNAE&H@{!|xn1|HyH!!&gZ43>g5Dz$ z$Rs%{u?ahmv&y=rQeoQiSo<C{mD!zJDoR!N_GD#3&*wYXDp~V)ZL6YY<xF6i&`Km6 zi9kGgu^<2RpMO9-!-4N`@$rS(DG!Fn(d&xmHWgwOss|eci&}VyQKT9kN3SbVsSvA} zr)rgb$TCU#mBH@IvYtilL$y=TyKAd6iL6x5Q}wK}uHB}ZwB<3at7Mtox!IF>dREEG zgr3)9sAO@)gwAc=N2jw^Cb5srv-+2>zP48153hgdUh##`Kd~??6g(xW?!R`{=O=|& z1?yPFxVOWi79L_)sh&LQGe{B@ViogL)%hy3XWjJEqZA8S*|}KnuC2}_vglSkPu1O< z3f3mS&9kzu*;B1zBuiE%^n5B>C5tO21aDQ;tegof6IzLcBN2#w671lA>FW-uy)odE zj=F7OcFKd{arCU%GoeDPLiJ#SU{MPXF^W{f<LJ*IsZ@wn%u}_>K4h6B{mNkXWm$Va z>_fFv(7S7^Gl{HJ&r|iRvaa2xnzZFH-LH~mcIReK=IL1_D-(KNkD-#q6%#tQc^{q5 zTA9Q?HqYu)AAVQuf`87Jes-_;UQaxvFgxYJQ=;nr*Dt+zQixTspI*hdU%{dl9%5Lj zo;>P)MG_Ta74uZp`6{z#-SpF=6bo6|xmfS6t<EH}=vF*W)!my4)+WErv$C$)Q>|ho zOI9ZId@A}kdRbgCA$Y5zX5~y^nb1lk9Em_&VL$%fAKj@uz(4%MI}~O|JQyBF&x*P# z#41z|HV78A@DQU&H9U^~43bKPSj9Y5tL#ITNz$(jc3+k?EBjFG6!h-e>P#Xl)$>$i zUCFZBRFk$mru$X0%<kOm$vi!)WMx9n>oHWaxMJtdZQe(xvsNatkIl2<mqYgB|M=T? zuHPWR7eD)sh1n4go)T5}{O+hitU`6CQ3s1!c!*J?T5ivZR4T+O=Bdi7es|VA>!zO` zrKsOh?PER#y}PzLljN+#^HjaAvaYFAn6}gCku0-2w^WQ|$;yPD&v&p@vgYsFRz=Oq znZU}qd441U;lV!rORm0attIf&{zd=J&8~YeJdU0fbybK}s2*$(ENbB)Mv-cG9AjOn zAfZW8-TZ!C*1FO?>uy!ltn6bx1-(ZikV$e@ViR^AXO(qLrNXr3G2O3{Wp?M5ic-}x eL$WfV=kpzGm8|)@wpCHHawf2HZl2$>=l=oKG<^F2 literal 0 HcmV?d00001 diff --git a/data/meshes/siggraph_asia/plane_hole.stl b/data/meshes/siggraph_asia/plane_hole.stl new file mode 100644 index 0000000000000000000000000000000000000000..f722d22c4eb84d026c731fcae2fe553fd856403e GIT binary patch literal 5484 zcmb7|e`r-@7{_0W{bA)QO;g+K78BI9wIA&VbN9Sg%MoExI3%<bYzx8Py4YZfm+j_C zLoG-xMd%Nqpt^IK*4#OFWd)Xzvu)+171bX>1VMil>3W~%ecyAx?>Q}Ke?8pue4g+3 z`M&2K&vjYHwyitbT3Zs&?by0Gv2;`GmX_8XWmV;MHHif~pI@J-SSbG2-zL*NF|kKd zdH#*Vaz$HXYRa|3T3dfOF%hUbN1s!z5g_;q5~hw2LZow`G5C?5OL~Le$uG|u4X(8Y z5H!o_LYit#^!`v*O_cF&HJCO;#1#<XmB{9jw5>*3zEiur3imMH!!D$$FD=LGj+X<$ zDcUZ`4K}}8G4MW-b`Q|7XG3l$C$J0akVxmc>qA#O3-ZCFndUumBQ@dXMBrSzQ#eV8 z`wwp8^Inz6dPjRt$f4h-$TicqC#UV#^><}0T(?}P@TevY`b+bjc=E5$m{3>zxg)w( zw2w4vaJSM3h%mF5pqdDzwF2ECRFNyw<v1b2(n2gP&hp)LTJ3}CI5$RkG+z-C_rMfT zJD!zwg#>BS=kctt3-!=#JS#d6N;jIDIVYbspg)}zcA<B7^M@l@S-<EcMmSj+f?ZjM zs3*kTr=Q`|TRug|CVy7y=?zo8XFJ|Yj=ZVs?w+@}&K!9>pjvN1_f^r*c<s$A7BZo( z_^(#!TG2kztikt{(#R2EW-&oE5lDv`?2KHQF2@NGmKLHw2<{$H`=C0`jS=ih5fb;n z6i_>!m34&#Y18L!RwcvZXR!<Q&}}>`IuA-WnwvSN$bE%f=smW%la=+0PGW?Ul_A)b zb%=WTJDsZE<jhpxpUv`m=2`>P{ZzN@yy2<O`@=J5onNzyLIP?g%p@lC(~Vf_GP4?> z?nhc{sDEpDdr)Ur)(O(ql@LUscbq#ZA)yO5N4*Bp&`$-bqOLGE>yY}`5oZOicylBs z&&qazcck;@!C7G!I)u+dBA=D@3l8}_?B{w9y9>-hCy}haZ)(qt4vp6}WHLeZYA^L* z>qhU`H|qu}Hh8JGuW$7JF4#9Px>lyP9R0!%UU^M@KRRdE`{hNu<X4}TdR4ctWI|m@ zmKU#NqUzRzNu-7Nv8kPteIS$ZzAb1@t-pB5S92RjW;F9$rPqkG5JzU$C!33Q<u-p@ z8jL+5nNV|mbb_=HFQ>b_pD$N>)i3PKp*qfWiJo*<AciUfMM&HOQ$TGYras!vr+1(; z<G4Zs9jd43ta|@3l~vb;QV+XO58bkcym)22?)A=$lP>0lI|=cU%4&(qYThTM0d}GH z*yi5nDytfm75YUdE}_y51}|3z52>tB1NT5Zx(D;$!Qpr3r+%3>NYAAPsQalN+**>% zKd<b2`<3FwAptcLW>VyNMO|iA1JwOU+wX^V2I}m}IzieJdLQ(Tb0;Mvbm8Wx7kOSq zU14t4p>?I7*5HaaM`H4<Y!`S(+B|*ivmLw8A$$(cD>{4Va!zehg0sRCv<_iXB&%Id zeJyJfJpsM9Q$20p-hkdeslM;(j2yjR>#X*xciqIitk+S0BP6Is!q$A&{Jf%yiITf= z^e#%Zor|>ASfbv*`|iyK?8*@61ZhnyE6#eS6ouY#Zk$-G-eAwDUFZsK?$kz`H1glU zs4FDwPTJM1L)+xcd$JxACf%sse`JLO<c5S0Lu%{8McIJoLRPgvxUL#iR`eSO6OHEP z5|5~?`fOG(7dN+hLd-p*-`nS?U+ZHF{*ZT^I>hgZ=hx|)-l?e;?W=sMbyg~2Su(u# z+@krnrHD{hlE+fIrZ-lkop(`5gqg(z)kGj2YVf~0<jQn8PKdCy5H|_I_b$D+qdLxY z33$_IS9T9f0kz{<SyxE>dseg&c42PlHlCGr70u0@Q!<~G`W;n+UFhB2+-5auvZ6ig zIU7CSC2Us1>NgH*;2x+a#GPHc`SkYm6nY=b>6NQ5Jn7AN@lxaVTXa3N<`ma^8w&!e z!#&jR!L{dpIxxnBx-xKlkFFIxfV2?PyLR)Lck~nnM3`AjP)!8Vp$0o6SEkExLWHG- zSl3<1|IbjX_Ca-=8zcC)vmzw!fhnLi@4=4L9-NhRg#>BS=drBnunYCjEuRNxrOt!1 mqVu41qq&)L8gR41F7zJT+{w!NMJF-B$;uGy$~r_nA^rh`pKk~N literal 0 HcmV?d00001 diff --git a/data/meshes/siggraph_asia/scale_spidey.stl b/data/meshes/siggraph_asia/scale_spidey.stl new file mode 100644 index 0000000000000000000000000000000000000000..598356b66795b25cdad222218e2ce8640f2f1967 GIT binary patch literal 51084 zcmb80cd&J5dEGw@*i?ZCV46WPu?@svY$D<eLg$K3W)i@Z0W%aEq{t?s2rwiu;Xnu` zIKmhVh+Y-Zu}p6|^4K&1#uO(MV<2>JD5eaZ+~4!u-+tHL_nbSE{l~d$-o4hd*7NN5 z>~p^F?tAM;KKMarJ?ymmpK$tF4?6RNTl|O99(e!L&br}m+~{AObi(x>`taX9;l|fL z_WyPK=;G4XE6`P6wLaz8u@m-=9lOF!#c%oPPcJy`?H}K;4sOLyfBNWBcqSEK*N5WR zvGsn9$>YKc_iG(^TzKr*``>V&C=8FI6?sOSYH;(P`OK@|1eJ9;lZpczeW=JY*?Cr~ zM5|A{?hda3d4}xbNHuw^SErr+m{immJz{PbQi;mPj@{%YpM3p(A1mvI$6ieL!l5{6 zu1HqmNwMCXdG6I-du;#MGM{2O5&Yn-H}8AW2hIoO8FB2Ay0Wd{mE$9?xy9-`cYosM z>_2_gN_>|~Jg@MLzVOTqxS4bfy8T7JGbzL>sHCFVDyW4A3hSnN@~E9i5*1?VrdkC* z*PG0qb$2SN*0OV_pm*2S$t1E;ZBKH$dsEqYDt6CGmf2J7bVsseWkT0e(JEP-G2xNZ zo#viNoWk~5z2U*nIpxByoVR(@&phW8@%5j5v%)`o#2Yu@`K+FQ?#CyESOt|-jC}=* zT6l<IrF!zHeMJ%#Vin6&$BymaNjI52>!zO`rC7<z&c%B7bx>y#Svj|5s_x!YcAkpe zvyx@@R6E^~ELoY*^;EP<7H3Sjd%E0Dtd&We!uDBR=4bD)`p$D+xq0IC{@Y6Yf}1{| z@QrWqwhh?1_N*R#!UHFTSOt|-jC}=*T6l<IrF!zHeMJ%#Vin6&J*&)~b<<CeQcUjI zxmfS6t<EH}a&F61-My*oJQcfVCCluocDf^3vNECTsp$8hEY6s4_jLLGW35c$6t>Um zq!<3{Q@HQm?Cr;&BEHSDUw$%}I~>@#_N*Rv$!AXru?i}w82btqweS$bN_Bg1=K<+% zDwCwzRQz0TGJDqDsaVO<Bd1{6uC3ED)ly;SeLqBHDmzcb?pet)d#Z;AUE`6gOz3(l z;P<SYs0qCuuEX?L*Q}h$a&E4}?nIzlU3lNsu?v4|^SGD(<w|_}YyL&yhkg7Z8!$YM z-YIYX`2P3z1BF-x>ng^+f<-Mn#IRD`4kjas3bBf1s!F!W>{&Pc^eDyTo}G*J?)SGk zlgM%kuG@Ln=hakpo{BLm|3!qt>?%y+`pl#Dl^vQY6}xBU8515k-RY{CD*Mon^z(i7 zv>(4_^Xb#yS9=M3-pAfn_-~%LDU5<+>?;-YlnU`+gJ4k$4>2C8hR4y#=vIYT#WGc^ zVCkN9)2|E;Ue=R)b}rVtYpXMfET`Z)3FY>zOl9Y(Fl~8EI<u=ViR&|uX<x}QNvc!P z{m9~s3BgCtN)MAb1=qW_{lE9+$Jf8^9`&I!R^m&&>Gp-W!-3`YtXA*1@uU!|;0~^0 z+^=9!3lA}@R8Jl?E0U-Xt5~M$elmO3O+P(KF}Y{wV!gYzI+MtvTk$egcW)|Krc$wc zR@OCps-5mgmaI(ZdMa8ai!&xXa=O!1%Ov(OX63gST=?Gh_>-@+x$Yl7qrSs|zx3lj zD*S`H{d!?|<2wW2;Z%rKs2*&Tu&9NH7)7e#arFI)R4T+O=BZTKhb)t%Uvm!>lY4e9 z)*J4)x0^(kQ*a$`J$hf6%Fa_^!t$7O&P0VtTpu1@MLRTADt6DxGbVIyuG>eaOAnJQ z{fb$41<;vqS=Zg?j&J|WN_>?Yf2c4!5e$!`XLa6fpFAnVDtM=<822k!)WSmyE7k4b zRV0ZDv5IA?O18=DSvURkD8=NSos0FJf4?$`EV>mhQ+4;If@LZdV^;b7Dp_VvwbSjc zc}-R(bUhWVlEoPl9y#6Vs$~-U7_;)~;d1?J{P)#gJp8ho<A3?*_QYSj;3q5auRQq% z8!)_a2fF`x=S&K*3M#1>`wAAd@DRgFb$gghcT<@p)hhV8-emTyyHhc_>ycA1?R;M? zQ!N#CUWsaIrn2)?j9KNrGP??sxIR3*U)iC3q{6u!o|R`z==E@Yrl?tE-R#5l>Uws+ zdhL(zu(|eUKVN$n{Q0~7ufo^6+Jg$~G459?cu%B4TprVX4i>fW5aW^R$)l3-E>a;@ zu}szdz|uYIrk@_2PF8j<*1Kz~Gl?vx;5rHAj{B9YZGI}odoWpMcW(AKdDN_uWfB#; zXXTmY++5d#pX=$WS=XM@ub7nx^okq4Wc8Gvd+G)M<JXVh6My~pFJ1UQo&3QI!0<S_ z`_H}QwUa`uf=VjJtYA?K4>7D%w}ba9lBf`?Sf;9Eo6Med(@&35tYl^9V!gYzI+MuC zxh+$5_olM*RP3IWEVHND>5gQ{%7m_`qE)guW5Oe+TeET|%elEezqeEOn-|<|^VTO{ zwLHMTaM5vvPyg7%3p>}buT<cX3i0^VL<@^rc!=>xb$fVkCzT4Zie)O4>)KbkXWjH` zkA7X(tn6bs1--krI+NtA#Pd{svSnRUsW5GMO!v8DnccaiVkApeCUl*-*+Hvhd7Z7h zQ&F>WCa`jDuFv-scQQULKYZQ4tIt00IZuB_VLmy*rs{pgeOHB8h3fgff<-Mn#3)id zdDNYhR4T+OmZ^GH_94q8>8D32Cim=ItasN|XA)UX!F9al_N+{0=czDZr%~rjRG7r| znMcja4o#Jc-LvwH37wnk=IM0lVUnfad|&as?H@03#karl*59k|>fk?o)0YZg?g1xU z0B#T8gM3d^Ay%P!zOP_W3lA}hRNF`YtDaOU#46^gTG!v(b<eu#rw2dRlY4e9*1MQ> z^*|<(<rG{Wv+_FwXJnZw)hc=y;*l(~qi|itxQfX#iHhB`@{9?OobGhhtZPr{NBZ%9 zGB3Q#`E~dCr<<L)C%)^$uU?qF3r4}w-GBTu7fuSX3f_Y%#;jmb3lA}@RJVi4NTNcl zVwtLvZ8Ce-O+P(Kv67XYi}mi>>P#YwZpF(~-My(`ZS&hcE9;s))hb4^WMx9vQ_(6} zoG~GIr=n)%OkkPNN+cYKKs+b$fQxRudFsnvRnJU-@ABn)7yk6;?q3)lN6(69CRB)3 zs2*$(ENbB)Mv-cG9KGX7r9!M?nW|OxA<HD`R|W?!{p^Q*sCEi^cWrehk(KIYs-9KW zwcAvawmhcK&t#e1x!IF>dREEGgs$r`RI)f@Lg%*ZqtjU{li0`hS>5rze}BsL-+A`t z4IlaZDdP7(|GdKYzw>i9;3-jc|J;9b`IQQ>3f5JO`xPu|;UR{V>dB)%bx5K@tYVp} zI^SgWtebv%lwu_-I~VKSwbhwKmQ!%u&bvOZrn2)??4Fe@v!{CIQL{>xNmLx375_4l zMJ*HVo-W^i(qlQd-LpFVly6?}xNBWwg$MXLm-ue^o%iOS-+-NK?-c5)5UWr<CJTZ^ zEj+|1QayQ0`$`3=Op<C9{9M<pbkDjw6_vz3?A$5n-L-WxiL6wcP;SpE>zXRnPIvwu zw658moBd55)4noqCRDA*P{~?ewVjITs$~-U(3|?>`xU=;{K>8Eym{TRU#{Olg7?1g zvxU#P&sl}1L@N-#&r~5+p&H(p6)bAuAx4pE6daw5R4T+OmZ@50AF@o6er0g*vYy<t zbFtoCTb)T{IR)48mfPK%%Fa_^!t$7O&P0VtT%UQ=zOqA8rDFH2JYz!V=DK}!y7Vx~ z(yy462t?g)T=R1m{PSPCU+pFEpI`Y_h0na+@f$Eaj-C~DRftun9&8XSYT+S9k!pAx zV_&Htp-EER{C-_;>|<GXr($x?&c%9<L?DyMatf{=o|UQWJQcfVCCluoo_S3B%Dg5~ z;oN#k{o1qgj0v5a>odi4)vRm6^g}W3SJ!*Vx9YdZr@iccd*XNhpL-VOH;Q0AdS9J? z&c*ilohb^j3f5JO`xPu|sjzOUCy$yHNmPibYb8B~Dzj(Zor;yL>|Ct(_}4s6CXwY7 zT+dY9y{YUx6=PQZ4-Oug%IvA0dDN_uWfB!mn#vyQjVx-J5NxINK(($}Ig?CiCH#t6 zi9ioH<IO9c)BoCiPuLUR@mW_Z%oFioc;kPh&il^0CxuuAl~jy<1&dmEh+(CA@~C7a zQ6W|_Pj!%Nli9Ow`nAV_VkIj(7wbLWS0<5_bDO7fr<lslQ!!>Gn`D{F?5TFTBU!RC zq3c6&(0R?uye2$yx-~0jk_pp~>f?TO%MX0N{tDu=54*#j_%^S;ZDF2>2csDKYW3<% z?D1qj3b6{-Rg8TFi&`qIo9gy38A()#scR)YTD5;&Hkm!^?o_N~W#?kO$JN8hB(j`> z>zS&%H<g{IV$3S{Ri-j~s)q+%lPXyzQQ@TF_2H~MW5Oe+TeET|nK1pRKlasW>zCE% z;8{Pq%AWWmCmmOqJ0EyTv;sZ<@^79LVinxmRg8TFi&}VyVWqk~OhytFViogLty^z0 zd)7@qJ@~o*|5wq6YNw!gF{gXGNo3Kjc$uoZ&$`?Ew$IACW_NBm-Ld17l?h$f!|r=l z<~8Aw)2&%KlVu;S&u4YxyIpLLr{F*Rx-<90xA@v=g?S<#+=+Zwz5iPKPdFSX#41=< zG4>TKYT+S<mFm$oh$Je+D(0zLx87v-tebv%@N>PAm7R<A9#;>INn|+%*X_LPtB|$L zuN6)fMY7E9+;X}jS+Y!`V)v{(vz(jjWbx=(Ig?D7ez3>=iZeXHf83QHT6+n6*1vr~ zVV;NwkNP0$st~JC4R5}$sD%d#>!un7M<*kd3Naq3ZhpV^zS2GG?o`yivXA8y^d5;o zCdpZe?WyzFebzOV3e%QHeG-6@Wp?M5ic-~`G+CL@^}K?ulC`{QI~6r6X96qd=K4qk zdhv;$s86+<U*)!Y;urk8RblRMV0iWZsP6ya)nAzuVinw}Rg8TFi&}VyVWqk~+*c$~ zAyzR@)w=a2vuEA((}SPum8|SstamY|&q0&OqFeDYRd;VHSlj%z&&s-HPqm71ze-jn zbbTng|DKh3O?c#VYgW!=*@x@%S@F$_C-{Huf8M>mtAn5NsXG?t8G3N%@ovrcHWgwO zs>@?~55l4r9%2-!ZV&ersZ@wn%u}^)UEkYv&${WSN2imOos0D@=CrR&BFibbK4#_p ziZimd`KcK1!DN};x!GU$!8dSFvP`04_pCf)!Xu|!-`kx@CQQHitnT_>FJ1o|b(_tj z_QWs!-op#C6Tv7ry8Cb4{`g5DR>3<>#h4W=YT+S<mFjkIRwPj&R<TUg@7&Cub<?js zc;!7JD?1nK4R?HJFo`U>70*-o9yArKZGPKlWnHtUTE$3~tW4;7Dq1CrGbRM@RMf1T z2`m#@iG(8&=wH6}@_Rh>aQBNpaZh~d6CPifCnLb{#^>M%|Kn9Ag;)iZRE&KEi&}Vy zVWqk~yow}IAyzR@)w=a2vuEA((}SPum8|SstamY|`;|##<=mF3x_eXEc`A0#N|xDE z?R3ZIV6rly>qF7~_pHoo!Xu|!vvMZOxw$@{6+4cn;BWY$N7vp3Kl!qcEX*_X;Lelx zD;4bBREW!Cr4AOg@DNis)pGmpKq?ht70XoPex-ZXO+P)x{mMR;Q_y={J+vmtS&5ga zdS7K-Q>id*r!iZy%<kNVqS-yGWMx9v^9rI{Z)9=CguAE9b+=X~v5zq;YTL(mPQK<I z&*@*~(tolie%CMkabcc_2g~hQJ>}xpofKjfR8leSSFosshZt6>Cyz=-5*1<<%Ty@W zo6Med(@&35tYl^9V!gYzI+MuCxh+$5_olM*RP3IWEVHND>5gQ{%7m_`qE)guW5Oe+ zTeET|%elEe5`n18Q}C~R)1Q_H_}+hac43}~2gBnS`$`2KsSpn~2o|;Q5K}kR@Hl$M zlS+kH#WGc^>_e7G(yt5-Ue+}$`%vu^^zPc~Od>1Q%T!}u$+Fv2JKgzvFcl_Itzsmz zL+hqunW|OxK`lFXZd(;KtE_86E8#s7fw&LydHzRdJ)-W3;IF*mL52C`1jFO#?ztzb z5UWr<*dSQc!b6NA)$lmR=b#D_nk3cD@7KP!>z;LYD(c>DAImA|efV?GGusr0XO%2d zEhl~WbI?>~cW(A)=i_rQQ;Ah)s_rKzYC^9E>O+c}Rn|43l}I?B72n%<3jXbnd0c&0 z2S4z6>%u%+5AHtvHxA$1RESlmp3e#vweS$5NcDVHq*5VPF;CUH{w}I})=fV>_}Smv z?PECwy^A@0XD~_5O1w<f@4>8VDix;fG`w;o%k0iA72_%<D-*gtu3$U#tjue|Bd1&6 z+nq@!Oh2lR?^h50+Y{^VbGzf7u_yk)4W3$<9SZI|-mfnAjO$Mdu?qIFig9m;MJ+tU zuu?sF)Kw&j3bBf1DwOL@X3x6mr$;GPva)lr-s9?_F^Md?6)#hD_ojli&97(WI~I>* znLX7`7j9q0WMx9vQ_(6}oG~GIr=n)%OkgcLC*ep0;z<Xd$N$@>{bD^E1HQ=zu2GmL z;=%C79f;>7RESlmhClWdENbB)Mv-b196c*isSvA}r$V!TUFz8n-Lr1`!R>=9DJwe{ z>kWIn2TdZ&DY!mnW%rzswarh(d{(J2iE0&N$J?Q)QgL`z^pkl_xO=+vk{%{m`pswc zTlarY{T0MX&%XYi_?(ZNSePf`!6-Po`?J6K(Mcgz!4v-~#;jmb3lA}@RJQ{=1Vj=Q zVin6&@YkEno^{g?rpJ0ED?1nKJ+2-)lgOf5@jR7xAXCBG=GU{5jYqP~o@%EHw|9K9 zGNJ3K=ze5z#)ROVikg)(fwk<Mgd-7%x;&4+`S&*|5AcaE{1=6JA|4EnW9%yxc%(u+ z*dSQc!b42mRKpurkyI+gDwe6x^}f<Q>!u$}kKR}Iv7Cb5BM~~2<gCQ=RPL0lYbq6{ zEsvGCl4W-1HWbYs`^vnTP<38GbUiEcn()Z!*1pms6Q*C+?qvOY=b!BVt;9w5y=ncf z8GNH>-Ka3n(1YdnzT)?eD#R*Om&Y_KSk%Hpj3U*ON8PXZZKw*die;+us^2^7o^{ht zk4`5mI~VKSwbhwKmQ!&3@T@o^Ynz{nac@tS*`1sHnWy(vvP`04_pCf)!Xu|!zjt;f znK1nh&x)tu&v@mnYcGK>`uxoc^9((>`|v$TT@_*#s>@@xuc(Cw3hSnN@|gCO3bLm{ z+=_nf-_h%yb<=OAs9D(u9*Omy->*!Pvl7o!IjgK|Dix-k->;HocIP$}bh7VJvr1Mb zbbVaGoRxV^2y3UJX5~y^ZJ(8&%=p~=$9JvYB0lzIn?3PK?|f@ve$xo<Jbn&-;;-&C zDa0!HeWZ%<9)v|LJjAe4J$cluNTNclVwtKZoY}K(`svYEQdV{@)*Hq6-fj|EbSqw_ z>h4ViYn$KpSy|WYsa7$PB`XuUo{Cn<;*1HwI~6O>WRmP0Ja#%R_xaRs?(qcwZ7=z} zJ@NNWd{$weln2A(=vn>f+`UO5Rzam!_>M&fi&}VyVWk@0NJbJBVin6&t;+0KH~re< zz-J{ZI~VIc5}`7Qteo3CmED`l&Qq~_R<g{V>Yi?Q(mOs`nb7rApj&TbamIwZr^|J> zRwi)@+h=vrmF`i01##-1ynavotyi31m?!1I-G%$=jE~)SQixUXw*akhvS?vZ3lA}@ zR8JmtzaohWv5IA?zV?|t>!zO`rC7<z&c%A8822la$f8^EGF86^O$BS4U(d?P;+8D4 zr&`5GmaI(ZdMd`O%xl6Ur(3gfCYdn(=I_CKe)Y!nsdniPpR*@^%h&&`F!y#aJ#h4_ zzJLC2P71LK?%=J+eFckJc!*)8x*hgawXaB`Labt$s{6_8SvURKgIChY%Fe}l!yWs| zB(msMJWpl!rh>K2uV>|CaZ8rjQ>|hoOI9XyJr%8z#TgTVcPeUD&IH!7a}v(?)jb|_ zulg&9Q(yDfd*W}t_rk(FDGw%1UkiSI_qO|gNwNR;5h%neSZ{@sRY5Hk)=f1$j=qW{ zQ6Z)-3f0Z;*Yzf|XWgBOm8|SstoPwrc}Blfj9Ix;lC{lm`>b-h`l%isz6b3vlYm_x ziky{GG$E{=ikj6j$<puetau9kqxXJS?IrLN{_|fI=81T4=W(atu0pIr_1J}IVNnYY zF^W{TNA4>XbZ(MVtKetvE8Vm1PDRbiKJZAa_u*N2W}9NnD)*IjO|_i#;aR0ZKh?t{ z_mwPXwVd?fS)o{7wWDXHhe_<i_4%xR_}1IkUF|{lIe$-l!XLh>Fn2z%srqy9oX6g2 zQixS>e{6-j5G^cf;UR{V>h^F}BvBz&u}p<>y~*rZH~re9U)L*H*|}KnuC2}_vglSk zPi6O}g0;=BXXP%$Cs}4swTh7}S((uFRJ2MKXG{p*si;{w6Ijd6NjMUL_~ym)_+R>! zx72ra@H21qhQd544~941ReWz#Ay%Ope(ypMENbB)Mv-cGW5<(9g;>Qrl`8v?Ws>wO zi+bU@>z<v9^&W|knM9UTa2@X|U*F$U$lB)D3U?ujWSQN$+0*1v-$j#U5*3GM#d}Z| z?qKU$Y4p)f>zb7_$%IzI5AOIb`d?msTJ64vzV3Z{;$QmUy9={J!6-O-r(EmdXHE*S z3ih#zv9DlJ3lA}@RJVi4NTNclVwtM1eP++P>8D4(M`UH^V!f;Dx_Tg!$f8^EGF5kP zDp=e6w$IACW>2+>kt|u6(DhWbN)~5K2;Qk!c_x!&=ireDbgzH-y?W~5dLRAYd*Y9M z`@@BKG6D>bqi6Mlmpo)rh*j|Xgo?4RU{MPXF|1U#gP(&WQ6W~bOjXG?nLX>KUwicH zdL=767wg@%)tN*V-HPX_yaSmE);7QGv$C$)Q>|hoOI9XyJr%8z#TgTVcPeUD&IFbT ztwh3+2*iHndHgTD{r$Cf!O#5odkXVJJQyBF?-cf~3b6{+gAIa3Ej+|1QVoxz@1&$s zAy%<WHSSlsXWjH`2VS}Eva)lr-f-vlcF!#5woEndSIb%HVcPOo@yd~@%<kM$0k@MS z%UP*drfQX}<yEs1>o7gmH7h&MgjT{2_L$YR&v-=r6~q@l`S*L`r~lxig?S<#jH0gv zKi_hrM^6f|3ZD2^G45BesD+0ZR;sDoJA|JkQ6W|_PX(KPGJDodzvlMqdL=767wbI| zp)!dqx)sk;dA~9htZjZhE7^D?%j~Ikx+7V#GNJ23L49XsUK1WU-I|p%$%N@Q65+xb zo`QeW*`KPt1is<RKT((`<-zbuRqrb5st~JCJ=iE=Q40?-id4fJ$w;L_tYV(3b-k~2 z&${W?+yh0;%08A;(0e38Ws;ngc%I6gl66g`!nB8HWh%2fx1k`-zDIrYOI9XyeOy6Q z?kn?}@W|=btenZR57$Q`T)30*X?f)*^=BXWoiBe!eGc-83WmoqJ_l8BPfUe)J}X$% z!b42mRJQ|NgGi-9tYVo8{(55{vP_bGFg^O-ZXc?hg5I#lz1<|TQoT$yJ_lvlZK|E_ zxVI<E?9R=erXFfm$;yPT>(MH9qb$zYxpQ0g(O1%1nZ!QEtla51@y(0p@t<_J57l=# z@F@@do5DOP51ta${fh5xD#R*O&-WE9YT+S9k?QvFDw0ZtSj9Y5>(=$XUH7b;etPh; zzqi}RateCS--9N}S&5gadZ%PvQ>ifR;aQo=?9Oc{=)kL(tW4<oxPqvdu&m`(+o`DU z?al<239UrJuFWgQIX`?<-Epq=+0X5XFZ$`H3$qi!McjYsSzY5ZkDU}^6}+QVjQ1cc zYT+S<mFmf(-h(7jAy%<Wg>t>g>{&Pc^eDwjR(3Addt5y<CXq$A;$^Dt-c+!*`Sq;! zcSyZs@ko~0Q|)x&_MJ3Ynb7rAv`Q9dObFhos98A^Sj)~yI1+()PJ-w3-+Z0t*E18~ z-#_`;g?Z{843DE{#WNEs#41z|HV78A@DQU&HN0^ZNu@%pg7r*=uAlwTJ?o|)Opku{ z!#<W%&>Qyn95hMJN<2^HPRY8aQeoQinD$k&%<kM$F_I-K6S}^AR^~O~k<+c`WSmJR zOuupU$ad#X?(Oju`~zO}qCN4oHqR@}lk#AA9KEl;{^HwB3b6_*wZh4wgGDVo#IRBg zkE5?5NmPhcEK{{AvuEA(D}#fV^-5NDF4ntit22qLoZB*0&&pJGo{BLmCyP&}GJC3f zx}B(Jm8?wYdMePZH?lZm!Xu|!vvMYx&`Koi+PrdbhUf8L^Mv!t1N=MZzPK<?%7crz z|1$QK3OrIFM$v2#ENbB)rf#a?ag2SXf`leXb@ThRXQg}A-KnTq*~fAUdXGdPljN+# zChR<RpLI>8!nEZv-LH~mcITFgQq^~cWMx9v^9r^~me<+3I~6r6X96qd=K4qk;`fd` zkAKo7Usk_^1b^|wa|`pNJQyBF?-YLTs6wnl^<aZwQ40?-id4hn=zT>h6=D_3RIRcP zStd!pGB|kY-#gofYNw!g*H&i|S*c#8>RDx7yG=D|%VXMC$uhfhvnTWPtdf-pUDso% zWO2rX&TZL8r?XZjv5(!e;wkt`yyDNx1N^#oy|OS*%7dpw)jb|6#41#G8g;O!g@+hL zs^yM-rGm~)l4=#@RnIf%o^^LB>UZ?^fk$G!=ieDjlCu(<&{ShzS=Ur5Oj{naeU%E6 zsGePqx?kC$byKlSHD=`*JNJ6HZXcznS!G=l=0xVRddipntbU8UI^$BOiqH9jpDoPq zQo(xktUmMJb0&pY1-~(EMSj16MJ+tUuu?sF)T~INLabt$s{6_8SvURk=qo8JI~VI+ zQ>{cGlgOf5@iJA<%2cqn`Sq;)B)}tCW>2*WxcweXRwi^k6|IuR854qcDpsD!B-uH5 zBm%wo9*?iTg1F_cetl2;?c05|Fi*sT;f;6IKb`!<Ng-Cj6aOlDvM6Cu3lA}@RKw%w zS&>AASj9XQn*BYz$?RD-{owY&u9uaai}i-xi9jZiMYrN*s_x!Yu(tVapOtmZo@y1{ zHK~%730)rw*v`tlCOmSwH7jSb?89}ck6GR0p-->Bg1F8-FMg`{k-vAb!aOMtMltr) zOYioqNg-CjUlOPo`wAAd@DRgFb$ghMBr3!z=BW;nZ8Ce-O+P)l7g^c4SZ@^bS$Rgk zRM>f`>XR*5+x%3_XT=nAR^puQ*jIL#NmT5fm1j(N<aAf*vFyW%%xCq&`#iQj)h_vi zFYk%pc-1cy=H3oQG4|CrZt?g@Ay&aBgNiXLSk%Hp3@g>`;Z-Dw3bBfLs)J;k%${}A zPmk_JR(3Addt5!VCXq$A;$^Dt-c+!*`Sq;wJ43R}o@%E%k|iq>x;_-$|GH*nUK8$~ z?*27dSu2xd=ireDpBKD*|1T-_|Jvc&U%kw!;y?KQr3&+;Jh=1N{nyWa&ZH2lpi(Pj zqlHB+JjAe4-5%~MlBf`?n5RO=y*;yM-SpF=6f0TTxmfSRv+|67sp!tzrT0~`w)t(J zmDj`U&TUNBuKAfPXQkrsteCJY+)cQ9y6mg;SoYyW4$q3`^uKb8%asTC7I*4B#uM@2 zo|HR<x+=sfRQHu@U3X3`JWyCS)pGk&hi+Af@kq6b?gy6cS$C(RW@R6$or2znXXTk~ ziZLs$1^JR?Dm_elcvhw|yK@@~YV&U5XR`1!q3f9ne(x(-%d56iQM1arCQQGP2$yfZ z>q+&gcG4{`cB=SVFaF6Mn0qA{9!Jk=?-fs(6k-*8GPJ^7hz=ID@DRgFH9U^qSGt?Z zB&lvbuS__zXWgBOl`K8TE;cRI$M>scs-@!atW0I+sTi|zvbbd`v!{CIQTr-cnb7rA zbU(5<V?yvwMa{~Yz{);cpYJQaxAENkS?67{zN>>TdVPO~=Sg`mX*hac@x4ujScU5H zsCO(nSk%Hpj3U+WMlw>V5UW_GYL$J+GD-Ti$AM3M7qt)7PC@UH2$e}>rFx#qcU9K4 z+f<YG@T{zBcIReK_R%{&S((uF_E5w7L>6aE=-lRgv}#?mawf|@T%XVCCV%;y+I?^O zzsH>_zT%HASD2j$?&{9!F)w++q!6oMAGbm_T3FP=Lkug`lSjP=NuolmVxFpX>rH0Q zy6M;41I0>Kb}rWY@T@$eUn;tD>f3#?w)t(J6;sSviN|ygJZe^Um`POZo|R`zc;s|z zR(8JZ!}a;Be(__^tEV2G^5`p{D*npZS1Qbt5#YWO&gvm=d(os2tKj*GR>(#Ri&}Vy zVWqk~{L~?d3bBfLs@APHnLX>KpC0^NuViKCV!aQ~$}{?<qB}oGRCnuSZS&hcE2fyU z5|8QPu|MJ3S9X|5R2-fas+_0^cTblqnI6kNoXAK-I`%8i<3HrAE7Uy-e9`*yg?UmQ z43DEf2idPG#41#mM@<$TENbB)Mv-cG9DQ#ml?t(nWvW)$hb)t%Ul|;{tm{2!AF7># z-d$UrNo1vZnW|@%b?r9Qq%DuxtgLHx=Vnjl=~*Q!6S}U)P|4zq37y-rk4|T;Oky9~ zXLa%Com+ne@!+5N`BTO3x#Cp{^Q1g@N>tt7=`k;x6k-+pC4q{bELvF9!b1!z)ssiP z2T7trtYVo8<$9CZvu^t7QHqtU>|Ct({5@zAS#&F2rt0oZ1#6pM&noZj$ufJYoo;u{ zYqBz->#1m!EY6q^yi-xLawf2ros)1R0#TRe@lXEktCa`%X=hxuFi*sT;c@h=sH;M( zLiJ#SU{MPXF^W{f<LLJwsZ@wnEK{}0K4h6B{mS6rWnHtf57kaV@5B4bGusq+>oN9~ z9(JpT3Fr6rWSQN$4Mn^3tdixdRP3IWXY9kdxo#i)>{;1)CQQHithf*Ix&4IS?t3Em z(`Q_^?vH$Og4@G)7579HVil_Avw}q}Jj5tcJ$cmqic~7ZD(0zL*WcT9&${W?+yg~@ z4%)|Z3VI)&m1njo4$mrCrdm$=@T^Q_cIRe)^I0X!S*h4PE6<ql$m!Os?0ngW>!j+P z4&r+oPr?871;^KSb?`5|{|be9QXUMCqu+ykZ&M*wp?a`Eu&9NH7)7e#jjKp16=D_3 zRIRcPStd!p_BimV@1pjh+9~Kg5}`7QtW?ia`5w%=cAIL_&i7Ta%<kOm$v*ljCMy%V z-X3bW_Odu*LgzN`qgDNH9A}aVtwh54tS<cGOY81)nM+>tRPpcrv#S?oCxW}WvpVj* zubdQO6}+QbAsa0$YT+S<mFmf(?pGvHAyzR@)w=a2vuEA(Ywm$!B`Z4@>kW6j2TdZ2 zZpHIdc5f<J+x&V~zGHDqmf2ISVqC>!WkT17g8K9$i!&w!?^M*RoC&OD=OpafWwHOl za}qp{|GL|Jqn?ccpMJl8EX<Sg;O06jo|8}^R-qb2-`zm4sD+0ZMXKR(^i?F43b6{- zM=CV?$?7>7-Lr1`!R>=yWM$`Ky<v}iWfECV!Szhl-E&6PHa`{fS*5}xs#T1AWrwCp z#o<}ePv$itb*(f!dRpt6Rn|43mGGX=>bZA+V*M4w>F@d0p7?5C_<CWUlm~Zpcgk09 z_M}N6R>9u_s2H<?MJ+tUuu?sF)cuMiD#R+5sk)!co^{htk5a5;W#?kOyS6%$$f8^E zGF5kPDp=e6w$IACW>2+>kt|u6(DhWbN)~5K2;QlvSveC}CbSX>M<NhscnbcNulZhi zfbaFbZx`l?crd(rf2{aPT@_*#s^QJ|6}9j{Vck@t;OM&psZ@yZNOkl3b-l3<Sti-3 zs9D*EYNw$0xGUge5?QIXCsU1mCChG8-P84x0By3&?%eFDJ-AD&FmEPQ-5#yswP$5s zJ9lob4?b7YTA9Q?^zPc~_`M^~<NwC5{-Ayb3I5#ezFU|l;=yuzR{Y*kg;<5^@~B-1 zf<-Mn#3)iddDN^(r9!M?nX0e7eaJFN`svZ{5#6(MvEC@g=b%YsIR)48)}v=-Dmzbw z3Cm+PD_Lew^~|GYl`NB}I6N!*kwq;NI=8Kg`n|I=S<cP%>Z1~YsLNCE$G&{5o@W4` z|Fs{NA5Y4I;f?zhbybK}sD?l8SFosshZsewQH;9-sZ@wn%u}_lXQg}AO~2+IC~8*r zv7Cb5BM~Z-<gCQ=RNjHIuBlX*c1#wJWSQN$4Fyc^SINqRu8%8-%6(;C6COF;nw2xj Kgz0ze*#85e3{lnq literal 0 HcmV?d00001 diff --git a/data/srdf/siggraph_asia/plane_hole.srdf b/data/srdf/siggraph_asia/plane_hole.srdf new file mode 100644 index 0000000..9362403 --- /dev/null +++ b/data/srdf/siggraph_asia/plane_hole.srdf @@ -0,0 +1,3 @@ +<?xml version="1.0"?> +<robot name="plane_hole"> +</robot> diff --git a/data/srdf/siggraph_asia/scale_spidey.srdf b/data/srdf/siggraph_asia/scale_spidey.srdf new file mode 100644 index 0000000..44ec95b --- /dev/null +++ b/data/srdf/siggraph_asia/scale_spidey.srdf @@ -0,0 +1,3 @@ +<?xml version="1.0"?> +<robot name="scale_spidey"> +</robot> diff --git a/data/urdf/siggraph_asia/plane_hole.urdf b/data/urdf/siggraph_asia/plane_hole.urdf new file mode 100644 index 0000000..4860cd8 --- /dev/null +++ b/data/urdf/siggraph_asia/plane_hole.urdf @@ -0,0 +1,19 @@ +<robot name="plane_hole"> + <link name="base_link"> + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/plane_hole.stl"/> + </geometry> + <material name="white"> + <color rgba="1 1 1 1"/> + </material> + </visual> + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/plane_hole.stl"/> + </geometry> + </collision> + </link> +</robot> diff --git a/data/urdf/siggraph_asia/scale_spidey.urdf b/data/urdf/siggraph_asia/scale_spidey.urdf new file mode 100644 index 0000000..5eba430 --- /dev/null +++ b/data/urdf/siggraph_asia/scale_spidey.urdf @@ -0,0 +1,19 @@ +<robot name="scale_spidey"> + <link name="base_link"> + <visual> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/scale_spidey.stl"/> + </geometry> + <material name="white"> + <color rgba="1 1 1 1"/> + </material> + </visual> + <collision> + <origin xyz="0 0 0" rpy="0 0 0" /> + <geometry> + <mesh filename="package://hpp-rbprm-corba/meshes/scale_spidey.stl"/> + </geometry> + </collision> + </link> +</robot> diff --git a/script/scenarios/demos/siggraph_asia/bezier_traj.py b/script/scenarios/demos/siggraph_asia/bezier_traj.py index 16611ae..9247bcf 100644 --- a/script/scenarios/demos/siggraph_asia/bezier_traj.py +++ b/script/scenarios/demos/siggraph_asia/bezier_traj.py @@ -47,16 +47,16 @@ def play_all_paths_qs(): if i % 2 == 0 : ppl(pid) -def test(stateid = 1, path = False, use_rand = False, just_one_curve = False, num_optim = 0, effector = False) : +def test(stateid = 1, path = False, use_rand = False, just_one_curve = False, num_optim = 0, effector = False, mu=0.5) : com_1 = __get_com(fullBody, configs[stateid]) com_2 = __get_com(fullBody, configs[stateid+1]) createPtBox(viewer.client.gui, 0, com_1, 0.01, [0,1,1,1.]) createPtBox(viewer.client.gui, 0, com_2, 0.01, [0,1,1,1.]) - data = gen_sequence_data_from_state(fullBody,stateid,configs, mu = 0.5) + data = gen_sequence_data_from_state(fullBody,stateid,configs, mu = mu) c_bounds_1 = get_com_constraint(fullBody, stateid, configs[stateid], limbsCOMConstraints, interm = False) c_bounds_mid = get_com_constraint(fullBody, stateid, configs[stateid], limbsCOMConstraints, interm = True) c_bounds_2 = get_com_constraint(fullBody, stateid, configs[stateid+1], limbsCOMConstraints, interm = False) - success, c_mid_1, c_mid_2 = solve_quasi_static(data, c_bounds = [c_bounds_1, c_bounds_2, c_bounds_mid], use_rand = use_rand, mu = 0.5) + success, c_mid_1, c_mid_2 = solve_quasi_static(data, c_bounds = [c_bounds_1, c_bounds_2, c_bounds_mid], use_rand = use_rand, mu = mu) #~ success, c_mid_1, c_mid_2 = solve_dyn(data, c_bounds = [c_bounds_1, c_bounds_2, c_bounds_mid], use_rand = use_rand) #~ success, c_mid_1, c_mid_2 = solve_dyn(data, c_bounds = [c_bounds_1, c_bounds_2]) @@ -174,18 +174,18 @@ def test_ineq(stateid, constraints, n_samples = 10, color=[1,1,1,1.]): #~ test_ineq(0, limbsCOMConstraints, 1000, [0,1,1,1]) -def gen(start = 0, len_con = 1, num_optim = 0, ine_curve =True, s = 1., effector = False): +def gen(start = 0, len_con = 1, num_optim = 0, ine_curve =True, s = 1., effector = False, mu =0.5): n_fail = 0; for i in range (start, start+len_con): viewer(configs[i]) - res = test(i, True, False, ine_curve,num_optim, effector) + res = test(i, True, False, ine_curve,num_optim, effector, mu) if(not res[0]): print "lp failed" createPtBox(viewer.client.gui, 0, res[1][0], 0.01, [1,0,0,1.]) createPtBox(viewer.client.gui, 0, res[2][0], 0.01, [1,0,0,1.]) found = False for j in range(10): - res = test(i, True, True, ine_curve, num_optim, effector) + res = test(i, True, True, ine_curve, num_optim, effector, mu) createPtBox(viewer.client.gui, 0, res[1][0], 0.01, [0,1,0,1.]) createPtBox(viewer.client.gui, 0, res[2][0], 0.01, [0,1,0,1.]) if res[0]: diff --git a/script/scenarios/demos/siggraph_asia/hrp2_model_no_arm.py b/script/scenarios/demos/siggraph_asia/hrp2_model_no_arm.py new file mode 100644 index 0000000..88c1178 --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/hrp2_model_no_arm.py @@ -0,0 +1,72 @@ +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.corbaserver.rbprm.rbprmfullbody import FullBody +from hpp.gepetto import Viewer + +import time + + + +packageName = "hrp2_14_description" +meshPackageName = "hrp2_14_description" +rootJointType = "freeflyer" +## +# Information to retrieve urdf and srdf files. +urdfName = "hrp2_14" +urdfSuffix = "_reduced" +srdfSuffix = "" + +fullBody = FullBody () + +fullBody.loadFullBodyModel(urdfName, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) + + +#~ AFTER loading obstacles + +rLegId = 'hrp2_rleg_rom' +rLeg = 'RLEG_JOINT0' +rLegOffset = [0,0,-0.105] +rLegNormal = [0,0,1] +rLegx = 0.09; rLegy = 0.05 +fullBody.addLimb(rLegId,rLeg,'',rLegOffset,rLegNormal, rLegx, rLegy, 10000, "manipulability", 0.1) + +lLegId = 'hrp2_lleg_rom' +lLeg = 'LLEG_JOINT0' +lLegx = 0.09; lLegy = 0.05 +lLegOffset = [0,0,-0.105] +lLegNormal = [0,0,1] +fullBody.addLimb(lLegId,lLeg,'',lLegOffset,rLegNormal, lLegx, lLegy, 10000, "manipulability", 0.1) + +#~ AFTER loading obstacles +larmId = 'hrp2_larm_rom' +larm = 'LARM_JOINT0' +lHand = 'LARM_JOINT5' +lArmOffset = [0,0,-0.1075] +lArmNormal = [0,0,1] +lArmx = 0.024; lArmy = 0.024 +#~ fullBody.addLimb(larmId,larm,lHand,lArmOffset,lArmNormal, lArmx, lArmy, 10000, "manipulability", 0.1, "_6_DOF", False,grasp = True) +#~ fullBody.addLimb(larmId,larm,lHand,lArmOffset,lArmNormal, lArmx, lArmy, 10000, "manipulability", 0.1, "_6_DOF", True) +#~ fullBody.addLimb(larmId,larm,lHand,lArmOffset,lArmNormal, lArmx, lArmy, 10000, "manipulability", 0.1, "_6_DOF") +#~ fullBody.addLimb(larmId,larm,lHand,lArmOffset,lArmNormal, lArmx, lArmy, 10000, "manipulability", 0.1, "_6_DOF") + + +rarmId = 'hrp2_rarm_rom' +rarm = 'RARM_JOINT0' +rHand = 'RARM_JOINT5' +rArmOffset = [0,0,-0.1075] +rArmNormal = [0,0,1] +rArmx = 0.024; rArmy = 0.024 +#disabling collision for hook +#~ fullBody.addLimb(rarmId,rarm,rHand,rArmOffset,rArmNormal, rArmx, rArmy, 10000, "manipulability", 0.1, "_6_DOF", False,grasp = True) +#~ fullBody.addLimb(rarmId,rarm,rHand,rArmOffset,rArmNormal, rArmx, rArmy, 10000, "manipulability", 0.1, "_6_DOF", True) +#~ fullBody.addLimb(rarmId,rarm,rHand,rArmOffset,rArmNormal, rArmx, rArmy, 10000, "manipulability", 0.1, "_6_DOF") + +fullBody.runLimbSampleAnalysis(rLegId, "jointLimitsDistance", True) +fullBody.runLimbSampleAnalysis(lLegId, "jointLimitsDistance", True) + + + +limbsCOMConstraints = { rLegId : {'file': "hrp2/RL_com.ineq", 'effector' : 'RLEG_JOINT5'}, + lLegId : {'file': "hrp2/LL_com.ineq", 'effector' : 'LLEG_JOINT5'}, + rarmId : {'file': "hrp2/RA_com.ineq", 'effector' : rHand}, + larmId : {'file': "hrp2/LA_com.ineq", 'effector' : lHand} } + diff --git a/script/scenarios/demos/siggraph_asia/plan_execute.py b/script/scenarios/demos/siggraph_asia/plan_execute.py index 024d03c..76457c2 100644 --- a/script/scenarios/demos/siggraph_asia/plan_execute.py +++ b/script/scenarios/demos/siggraph_asia/plan_execute.py @@ -44,18 +44,18 @@ def rootPath(): r.client.gui.setVisibility("hyq", "ON") tp.cl.problem.selectProblem("default") -def genPlan(stepsize=0.1): +def genPlan(stepsize=0.1, rob = 2): r.client.gui.setVisibility("hrp2_14", "ON") tp.cl.problem.selectProblem("default") tp.r.client.gui.setVisibility("toto", "OFF") tp.r.client.gui.setVisibility("hrp2_trunk_flexible", "OFF") global configs start = time.clock() - configs = fullBody.interpolate(stepsize, 1, 2, True) + configs = fullBody.interpolate(stepsize, 1, rob, True) end = time.clock() print "Contact plan generated in " + str(end-start) + "seconds" -def contactPlan(step = 0.5): +def contactPlan(step = 0.5, rob = 2): r.client.gui.setVisibility("hyq", "ON") tp.cl.problem.selectProblem("default") tp.r.client.gui.setVisibility("toto", "OFF") @@ -82,9 +82,12 @@ def d(step=0.1): genPlan(step) return configs -def e(step = 0.5): +def e(step = 0.5, rob = 2, qs=None): + if(qs != None): + global configs + configs = qs[:] print "displaying contact plan" - contactPlan(step) + contactPlan(step, rob) r = None tp = None diff --git a/script/scenarios/demos/siggraph_asia/plane_hole_hrp2_interp.py b/script/scenarios/demos/siggraph_asia/plane_hole_hrp2_interp.py new file mode 100644 index 0000000..f18f7dd --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/plane_hole_hrp2_interp.py @@ -0,0 +1,57 @@ +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.corbaserver.rbprm.rbprmfullbody import FullBody +from hpp.gepetto import Viewer +from hpp.gepetto import PathPlayer + +import plane_hole_hrp2_path as path_planner +#~ import hrp2_model as model +import hrp2_model_no_arm as model +from hrp2_model import * +import time + + +ps = path_planner.ProblemSolver( model.fullBody ) +r = path_planner.Viewer (ps, viewerClient=path_planner.r.client) +fullBody = model.fullBody +fullBody.setJointBounds ("base_joint_xyz", [-0.135,5, -1, 1, 0, 2.2]) +pp = PathPlayer (fullBody.client.basic, r) + +from plan_execute import a, b, c, d, e, init_plan_execute +init_plan_execute(model.fullBody, r, path_planner, pp) + +q_0 = model.fullBody.getCurrentConfig(); +#~ fullBody.createOctreeBoxes(r.client.gui, 1, rarmId, q_0,) +q_goal = model.fullBody.getCurrentConfig(); q_goal[0:7] = path_planner.q_goal[0:7] + + +q_init = [ + 0, 0, 0.58, 1.0, 0.0 , 0.0, 0.0, # Free flyer 0-6 + 0.0, 0.0, 0.0, 0.0, # CHEST HEAD 7-10 + 0.261799388, 0.174532925, 0.0, -0.523598776, 0.0, 0.0, 0.17, # LARM 11-17 + 0.261799388, -0.174532925, 0.0, -0.523598776, 0.0, 0.0, 0.17, # RARM 18-24 + 0.0, 0.0, -0.453785606, 0.872664626, -0.41887902, 0.0, # LLEG 25-30 + 0.0, 0.0, -0.453785606, 0.872664626, -0.41887902, 0.0, # RLEG 31-36 + ]; r (q_init) + +q_init[0:7] = path_planner.q_init[0:7] + +model.fullBody.setCurrentConfig (q_goal) +#~ r(q_goal) +q_goal = model.fullBody.generateContacts(q_goal, [0,0,1]) +q_init = model.fullBody.generateContacts(q_init, [0,0,1]) +#~ r(q_goal) + +#~ fullBody.setStartState(q_init,[rLegId,lLegId,rarmId]) #,rarmId,larmId]) +model.fullBody.setStartState(q_init,[model.lLegId,rLegId]) #,rarmId,larmId]) +fullBody.setEndState(q_goal,[rLegId,lLegId])#,rarmId,larmId]) + +configs = d(0.005); e(0.01) + +from bezier_traj import * +init_bezier_traj(model.fullBody, r, pp, configs, model.limbsCOMConstraints) +#~ AFTER loading obstacles + + +#~ test_ineq(0,{ rLegId : {'file': "hrp2/RL_com.ineq", 'effector' : 'RLEG_JOINT5'}}, 1000, [1,0,0,1]) +#~ test_ineq(0,{ lLegId : {'file': "hrp2/LL_com.ineq", 'effector' : 'LLEG_JOINT5'}}, 1000, [0,0,1,1]) +#~ gen(0,1) diff --git a/script/scenarios/demos/siggraph_asia/plane_hole_hrp2_path.py b/script/scenarios/demos/siggraph_asia/plane_hole_hrp2_path.py new file mode 100644 index 0000000..bff1ce0 --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/plane_hole_hrp2_path.py @@ -0,0 +1,109 @@ +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.gepetto import Viewer +from hpp.corbaserver import Client +from hpp.corbaserver.robot import Robot as Parent + +class Robot (Parent): + rootJointType = 'freeflyer' + packageName = 'hpp-rbprm-corba' + meshPackageName = 'hpp-rbprm-corba' + # URDF file describing the trunk of the robot HyQ + urdfName = 'hrp2_trunk_flexible' + urdfSuffix = "" + srdfSuffix = "" + def __init__ (self, robotName, load = True): + Parent.__init__ (self, robotName, self.rootJointType, load) + self.tf_root = "base_footprint" + self.client.basic = Client () + self.load = load + + +rootJointType = 'freeflyer' +packageName = 'hpp-rbprm-corba' +meshPackageName = 'hpp-rbprm-corba' +urdfName = 'hrp2_trunk_flexible' +urdfNameRoms = ['hrp2_larm_rom','hrp2_rarm_rom','hrp2_lleg_rom','hrp2_rleg_rom'] +urdfSuffix = "" +srdfSuffix = "" + +rbprmBuilder = Builder () + +rbprmBuilder.loadModel(urdfName, urdfNameRoms, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +rbprmBuilder.setJointBounds ("base_joint_xyz", [0,5, -1, 1, 0, 2.2]) +#~ rbprmBuilder.setFilter(['hrp2_rarm_rom','hrp2_lleg_rom','hrp2_rleg_rom']) +rbprmBuilder.setAffordanceFilter('hrp2_lleg_rom', ['Support',]) +rbprmBuilder.setAffordanceFilter('hrp2_rleg_rom', ['Support']) +rbprmBuilder.setAffordanceFilter('hrp2_rarm_rom', ['Support',]) +rbprmBuilder.setAffordanceFilter('hrp2_larm_rom', ['Support']) +#~ rbprmBuilder.setNormalFilter('hrp2_rarm_rom', [0,0,1], 0.5) +#~ rbprmBuilder.setNormalFilter('hrp2_lleg_rom', [0,0,1], 0.9) +#~ rbprmBuilder.setNormalFilter('hrp2_rleg_rom', [0,0,1], 0.9) +#~ rbprmBuilder.setNormalFilter('hyq_rhleg_rom', [0,0,1], 0.9) +rbprmBuilder.boundSO3([-0.,0,-1,1,-1,1]) + +#~ from hpp.corbaserver.rbprm. import ProblemSolver +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver + +ps = ProblemSolver( rbprmBuilder ) + +r = Viewer (ps) + + +q_init = rbprmBuilder.getCurrentConfig (); +q_init [0:3] = [0, 0, 0.58]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +q_init [0:3] = [0.1, 0, 0.58]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +#~ q_init [0:3] = [0, -0.63, 0.6]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +#~ q_init [3:7] = [ 0.98877108, 0. , 0.14943813, 0. ] + +q_goal = q_init [::] +#~ q_goal [3:7] = [ 0.98877108, 0. , 0.14943813, 0. ] +q_goal [0:3] = [5, 0, 0.58]; r (q_goal) +#~ q_goal [0:3] = [1.2, -0.65, 1.1]; r (q_goal) + +#~ ps.addPathOptimizer("GradientBased") +ps.addPathOptimizer("RandomShortcut") +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) + +from hpp.corbaserver.affordance.affordance import AffordanceTool +afftool = AffordanceTool () +afftool.setAffordanceConfig('Support', [0.5, 0.03, 0.00005]) +afftool.loadObstacleModel (packageName, "plane_hole", "planning", r) +#~ afftool.analyseAll() +afftool.visualiseAffordances('Support', r, [0.25, 0.5, 0.5]) +afftool.visualiseAffordances('Lean', r, [0, 0, 0.9]) + +ps.client.problem.selectConFigurationShooter("RbprmShooter") +ps.client.problem.selectPathValidation("RbprmPathValidation",0.05) +#~ ps.solve () +t = ps.solve () + +print t; +if isinstance(t, list): + t = t[0]* 3600000 + t[1] * 60000 + t[2] * 1000 + t[3] +f = open('log.txt', 'a') +f.write("path computation " + str(t) + "\n") +f.close() + + +from hpp.gepetto import PathPlayer +pp = PathPlayer (rbprmBuilder.client.basic, r) +#~ pp.fromFile("/home/stonneau/dev/hpp/src/hpp-rbprm-corba/script/paths/stair.path") +#~ +#~ pp (2) +#~ pp (0) + +#~ pp (1) +#~ pp.toFile(1, "/home/stonneau/dev/hpp/src/hpp-rbprm-corba/script/paths/stair.path") +#~ rbprmBuilder.exportPath (r, ps.client.problem, 1, 0.01, "stair_bauzil_hrp2_path.txt") + +cl = Client() +cl.problem.selectProblem("rbprm_path") +rbprmBuilder2 = Robot ("toto") +ps2 = ProblemSolver( rbprmBuilder2 ) +cl.problem.selectProblem("default") +cl.problem.movePathToProblem(1,"rbprm_path",rbprmBuilder.getAllJointNames()) +r2 = Viewer (ps2, viewerClient=r.client) +r.client.gui.setVisibility("toto", "OFF") +r.client.gui.setVisibility("hrp2_trunk_flexible", "OFF") +#~ r2(q_far) diff --git a/script/scenarios/demos/siggraph_asia/spiderman/bezier_traj.py b/script/scenarios/demos/siggraph_asia/spiderman/bezier_traj.py new file mode 100644 index 0000000..16611ae --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/spiderman/bezier_traj.py @@ -0,0 +1,225 @@ +from gen_data_from_rbprm import * + +from hpp.corbaserver.rbprm.tools.com_constraints import get_com_constraint +from hpp.gepetto import PathPlayer + +#computing com bounds 0 and 1 +def __get_com(robot, config): + save = robot.getCurrentConfig() + robot.setCurrentConfig(config) + com = robot.getCenterOfMass() + robot.setCurrentConfig(save) + return com + +from numpy import matrix, asarray +from numpy.linalg import norm +from spline import bezier + + +def __curveToWps(curve): + return asarray(curve.waypoints().transpose()).tolist() + + +def __Bezier(wps, init_acc = [0.,0.,0.], end_acc = [0.,0.,0.], init_vel = [0.,0.,0.], end_vel = [0.,0.,0.]): + c = curve_constraints(); + c.init_vel = matrix(init_vel); + c.end_vel = matrix(end_vel); + c.init_acc = matrix(init_acc); + c.end_acc = matrix(end_acc); + matrix_bezier = matrix(wps).transpose() + curve = bezier(matrix_bezier, c) + return __curveToWps(curve), curve + #~ return __curveToWps(bezier(matrix_bezier)) + +allpaths = [] + +def play_all_paths(): + for _, pid in enumerate(allpaths): + ppl(pid) + +def play_all_paths_smooth(): + for i, pid in enumerate(allpaths): + if i % 2 == 1 : + ppl(pid) + +def play_all_paths_qs(): + for i, pid in enumerate(allpaths): + if i % 2 == 0 : + ppl(pid) + +def test(stateid = 1, path = False, use_rand = False, just_one_curve = False, num_optim = 0, effector = False) : + com_1 = __get_com(fullBody, configs[stateid]) + com_2 = __get_com(fullBody, configs[stateid+1]) + createPtBox(viewer.client.gui, 0, com_1, 0.01, [0,1,1,1.]) + createPtBox(viewer.client.gui, 0, com_2, 0.01, [0,1,1,1.]) + data = gen_sequence_data_from_state(fullBody,stateid,configs, mu = 0.5) + c_bounds_1 = get_com_constraint(fullBody, stateid, configs[stateid], limbsCOMConstraints, interm = False) + c_bounds_mid = get_com_constraint(fullBody, stateid, configs[stateid], limbsCOMConstraints, interm = True) + c_bounds_2 = get_com_constraint(fullBody, stateid, configs[stateid+1], limbsCOMConstraints, interm = False) + success, c_mid_1, c_mid_2 = solve_quasi_static(data, c_bounds = [c_bounds_1, c_bounds_2, c_bounds_mid], use_rand = use_rand, mu = 0.5) + #~ success, c_mid_1, c_mid_2 = solve_dyn(data, c_bounds = [c_bounds_1, c_bounds_2, c_bounds_mid], use_rand = use_rand) + #~ success, c_mid_1, c_mid_2 = solve_dyn(data, c_bounds = [c_bounds_1, c_bounds_2]) + + print "$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$ calling effector", effector + paths_ids = [] + if path and success: + #~ fullBody.straightPath([c_mid_1[0].tolist(),c_mid_2[0].tolist()]) + #~ fullBody.straightPath([c_mid_2[0].tolist(),com_2]) + if just_one_curve: + print "just one curve" + bezier_0, curve = __Bezier([com_1,c_mid_1[0].tolist(),c_mid_2[0].tolist(),com_2]) + createPtBox(viewer.client.gui, 0, c_mid_1[0].tolist(), 0.01, [0,1,0,1.]) + createPtBox(viewer.client.gui, 0, c_mid_2[0].tolist(), 0.01, [0,1,0,1.]) + + partions = [0.,0.2,0.8,1.] + p0 = fullBody.generateCurveTrajParts(bezier_0,partions) + #testing intermediary configurations + print 'wtf', partions[1], " " + com_interm1 = curve(partions[1]) + com_interm2 = curve(partions[2]) + print "com_1", com_1 + success_proj1 = project_com_colfree(fullBody, stateid , asarray((com_interm1).transpose()).tolist()[0]) + success_proj2 = project_com_colfree(fullBody, stateid+1, asarray((com_interm2).transpose()).tolist()[0]) + + if not success_proj1: + print "proj 1 failed" + return False, c_mid_1, c_mid_2, paths_ids + + if not success_proj2: + print "proj 2 failed" + return False, c_mid_1, c_mid_2, paths_ids + + print "p0", p0 + #~ pp.displayPath(p0+1) + #~ pp.displayPath(p0+2) + ppl.displayPath(p0) + #~ pp.displayPath(p0+1) + #~ pp.displayPath(p0+2) + #~ pp.displayPath(p0+3) + if(effector): + print "$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$$ calling effector" + paths_ids = [int(el) for el in fullBody.effectorRRT(stateid,p0+1,p0+2,p0+3,num_optim)] + else: + paths_ids = [int(el) for el in fullBody.comRRTFromPos(stateid,p0+1,p0+2,p0+3,num_optim)] + + else: + + success_proj1 = project_com_colfree(fullBody, stateid , c_mid_1[0].tolist()) + success_proj2 = project_com_colfree(fullBody, stateid+1, c_mid_2[0].tolist()) + + if not success_proj1: + print "proj 1 failed" + return False, c_mid_1, c_mid_2, paths_ids + + if not success_proj2: + print "proj 2 failed" + return False, c_mid_1, c_mid_2, paths_ids + + print "three curves" + bezier_0, curve = __Bezier([com_1,c_mid_1[0].tolist()] , end_acc = c_mid_1[1].tolist() , end_vel = [0.,0.,0.]) + bezier_1, curve = __Bezier([c_mid_1[0].tolist(),c_mid_2[0].tolist()], end_acc = c_mid_2[1].tolist(), init_acc = c_mid_1[1].tolist(), init_vel = [0.,0.,0.], end_vel = [0.,0.,0.]) + bezier_2, curve = __Bezier([c_mid_2[0].tolist(),com_2] , init_acc = c_mid_2[1].tolist(), init_vel = [0.,0.,0.]) + + p0 = fullBody.generateCurveTraj(bezier_0) + print "p0", p0 + fullBody.generateCurveTraj(bezier_1) + fullBody.generateCurveTraj(bezier_2) + ppl.displayPath(p0) + ppl.displayPath(p0+1) + ppl.displayPath(p0+2) + paths_ids = [int(el) for el in fullBody.comRRTFromPos(stateid,p0,p0+1,p0+2,num_optim)] + #~ paths_ids = [] + global allpaths + allpaths += paths_ids[:-1] + #~ allpaths += [paths_ids[-1]] + #~ pp(paths_ids[-1]) + + #~ return success, paths_ids, c_mid_1, c_mid_2 + return success, c_mid_1, c_mid_2, paths_ids +#~ data = gen_sequence_data_from_state(fullBody,3,configs) + +#~ pp(29),pp(9),pp(17) +from hpp.corbaserver.rbprm.tools.path_to_trajectory import * + + +def createPtBox(gui, winId, config, res = 0.01, color = [1,1,1,0.3]): + resolution = res + global scene + global b_id + boxname = scene+"/"+str(b_id) + b_id += 1 + gui.addBox(boxname,resolution,resolution,resolution, color) + gui.applyConfiguration(boxname,[config[0],config[1],config[2],1,0,0,0]) + gui.addSceneToWindow(scene,winId) + gui.refresh() + +def test_ineq(stateid, constraints, n_samples = 10, color=[1,1,1,1.]): + Kin = get_com_constraint(fullBody, stateid, configs[stateid], constraints, interm = False) + #~ print "kin ", Kin + #create box around current com + fullBody.setCurrentConfig(configs[stateid]) + com = fullBody.getCenterOfMass() + bounds_c = flatten([[com[i]-1., com[i]+1.] for i in range(3)]) # arbitrary + for i in range(n_samples): + c = array([uniform(bounds_c[2*i], bounds_c[2*i+1]) for i in range(3)]) + print "c: ", c + if(Kin[0].dot(c)<=Kin[1]).all(): + print "boundaries satisfied" + createPtBox(viewer.client.gui, 0, c, 0.01, color) + +#~ test_ineq(0,{ rLegId : {'file': "hrp2/RL_com.ineq", 'effector' : 'RLEG_JOINT5'}}, 1000, [1,0,0,1]) +#~ test_ineq(0,{ lLegId : {'file': "hrp2/LL_com.ineq", 'effector' : 'LLEG_JOINT5'}}, 1000, [0,1,0,1]) +#~ test_ineq(0,{ rLegId : {'file': "hrp2/RA_com.ineq", 'effector' : rHand}}, 1000, [0,0,1,1]) +#~ test_ineq(0,{ rLegId : {'file': "hrp2/RL_com.ineq", 'effector' : 'RLEG_JOINT5'}}, 1000, [0,1,1,1]) +#~ test_ineq(0, limbsCOMConstraints, 1000, [0,1,1,1]) + + +def gen(start = 0, len_con = 1, num_optim = 0, ine_curve =True, s = 1., effector = False): + n_fail = 0; + for i in range (start, start+len_con): + viewer(configs[i]) + res = test(i, True, False, ine_curve,num_optim, effector) + if(not res[0]): + print "lp failed" + createPtBox(viewer.client.gui, 0, res[1][0], 0.01, [1,0,0,1.]) + createPtBox(viewer.client.gui, 0, res[2][0], 0.01, [1,0,0,1.]) + found = False + for j in range(10): + res = test(i, True, True, ine_curve, num_optim, effector) + createPtBox(viewer.client.gui, 0, res[1][0], 0.01, [0,1,0,1.]) + createPtBox(viewer.client.gui, 0, res[2][0], 0.01, [0,1,0,1.]) + if res[0]: + break + if not res[0]: + n_fail += 1 + print "n_fail ", n_fail + + a = gen_trajectory_to_play(fullBody, ppl, allpaths, flatten([[s*0.2, s* 0.6, s* 0.2] for _ in range(len(allpaths) / 3)])) + return a + +viewer = None +tp = None +ppl = None +fullBody = None +b_id = 0 +scene = "bos" + +def clean_path(): + global allpaths + allpaths = [] + + +def init_bezier_traj(robot, r, pplayer, qs, comConstraints): + global viewer + global tp + global ppl + global fullBody + global viewer + global configs + configs = qs + viewer = r + ppl = pplayer + fullBody = robot + viewer.client.gui.createScene(scene) + global limbsCOMConstraints + limbsCOMConstraints = comConstraints diff --git a/script/scenarios/demos/siggraph_asia/spiderman/log.txt b/script/scenarios/demos/siggraph_asia/spiderman/log.txt new file mode 100644 index 0000000..2b3f045 --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/spiderman/log.txt @@ -0,0 +1,26 @@ +path computation 7 +path computation 5 +path computation 8 +path computation 2 +path computation 5 +path computation 2 +path computation 2 +path computation 4 +path computation 2 +path computation 1 +path computation 1 +path computation 2 +path computation 1 +path computation 1 +path computation 2 +path computation 2 +path computation 1 +path computation 2 +path computation 2 +path computation 1 +path computation 3 +path computation 1 +path computation 4 +path computation 1 +path computation 1 +path computation 1 diff --git a/script/scenarios/demos/siggraph_asia/spiderman/plan_execute.py b/script/scenarios/demos/siggraph_asia/spiderman/plan_execute.py new file mode 100644 index 0000000..024d03c --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/spiderman/plan_execute.py @@ -0,0 +1,103 @@ +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.corbaserver.rbprm.rbprmfullbody import FullBody +from hpp.gepetto import Viewer + +import time + +from hpp.corbaserver.rbprm.tools.cwc_trajectory_helper import step, clean,stats, saveAllData, play_traj +from hpp.gepetto import PathPlayer + +def act(i, numOptim = 0, use_window = 0, friction = 0.5, optim_effectors = True, verbose = False, draw = False): + return step(fullBody, configs, i, numOptim, pp, limbsCOMConstraints, 0.4, optim_effectors = optim_effectors, time_scale = 20., useCOMConstraints = True, use_window = use_window, + verbose = verbose, draw = draw) + +def play(frame_rate = 1./24.): + play_traj(fullBody,pp,frame_rate) + +def saveAll(name): + saveAllData(fullBody, r, name) + + +def initConfig(): + r.client.gui.setVisibility("hrp2_14", "ON") + tp.cl.problem.selectProblem("default") + tp.r.client.gui.setVisibility("toto", "OFF") + tp.r.client.gui.setVisibility("hrp2_trunk_flexible", "OFF") + r(q_init) + +def endConfig(): + r.client.gui.setVisibility("hrp2_14", "ON") + tp.cl.problem.selectProblem("default") + tp.r.client.gui.setVisibility("toto", "OFF") + tp.r.client.gui.setVisibility("hrp2_trunk_flexible", "OFF") + r(q_goal) + + +def rootPath(): + tp.cl.problem.selectProblem("rbprm_path") + r.client.gui.setVisibility("hrp2_14", "OFF") + tp.r.client.gui.setVisibility("toto", "OFF") + r.client.gui.setVisibility("hyq", "OFF") + r.client.gui.setVisibility("hrp2_trunk_flexible", "ON") + tp.pp(0) + r.client.gui.setVisibility("hrp2_trunk_flexible", "OFF") + r.client.gui.setVisibility("hyq", "ON") + tp.cl.problem.selectProblem("default") + +def genPlan(stepsize=0.1): + r.client.gui.setVisibility("hrp2_14", "ON") + tp.cl.problem.selectProblem("default") + tp.r.client.gui.setVisibility("toto", "OFF") + tp.r.client.gui.setVisibility("hrp2_trunk_flexible", "OFF") + global configs + start = time.clock() + configs = fullBody.interpolate(stepsize, 1, 2, True) + end = time.clock() + print "Contact plan generated in " + str(end-start) + "seconds" + +def contactPlan(step = 0.5): + r.client.gui.setVisibility("hyq", "ON") + tp.cl.problem.selectProblem("default") + tp.r.client.gui.setVisibility("toto", "OFF") + tp.r.client.gui.setVisibility("hyq_trunk_large", "OFF") + for i in range(0,len(configs)): + r(configs[i]); + time.sleep(step) + + +def a(): + print "initial configuration" + initConfig() + +def b(): + print "end configuration" + endConfig() + +def c(): + print "displaying root path" + rootPath() + +def d(step=0.1): + print "computing contact plan" + genPlan(step) + return configs + +def e(step = 0.5): + print "displaying contact plan" + contactPlan(step) + +r = None +tp = None +pp = None +fullBody = None + +def init_plan_execute(robot, viewer, pathplanner, pplayer): + global r + global tp + global pp + global fullBody + r = viewer + tp = pathplanner + pp = pplayer + fullBody = robot + diff --git a/script/scenarios/demos/siggraph_asia/spiderman/run.sh b/script/scenarios/demos/siggraph_asia/spiderman/run.sh new file mode 100755 index 0000000..c249455 --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/spiderman/run.sh @@ -0,0 +1,8 @@ +#!/bin/bash + +gepetto-viewer-server & +hpp-rbprm-server & +ipython -i --no-confirm-exit ./$1 + +pkill -f 'gepetto-viewer-server' +pkill -f 'hpp-rbprm-server' diff --git a/script/scenarios/demos/siggraph_asia/spiderman/rund.sh b/script/scenarios/demos/siggraph_asia/spiderman/rund.sh new file mode 100755 index 0000000..eab7645 --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/spiderman/rund.sh @@ -0,0 +1,6 @@ +#!/bin/bash + +gepetto-viewer-server & +ipython -i --no-confirm-exit ./$1 + +pkill -f 'gepetto-viewer-server' diff --git a/script/scenarios/demos/siggraph_asia/spiderman/scale_hrp2_path.py b/script/scenarios/demos/siggraph_asia/spiderman/scale_hrp2_path.py new file mode 100644 index 0000000..271ddc4 --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/spiderman/scale_hrp2_path.py @@ -0,0 +1,117 @@ +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.gepetto import Viewer +from hpp.corbaserver import Client +from hpp.corbaserver.robot import Robot as Parent + +class Robot (Parent): + rootJointType = 'freeflyer' + packageName = 'hpp-rbprm-corba' + meshPackageName = 'hpp-rbprm-corba' + # URDF file describing the trunk of the robot HyQ + urdfName = 'hrp2_trunk_flexible' + urdfSuffix = "" + srdfSuffix = "" + def __init__ (self, robotName, load = True): + Parent.__init__ (self, robotName, self.rootJointType, load) + self.tf_root = "base_footprint" + self.client.basic = Client () + self.load = load + + +rootJointType = 'freeflyer' +packageName = 'hpp-rbprm-corba' +meshPackageName = 'hpp-rbprm-corba' +urdfName = 'hrp2_trunk_flexible' +urdfNameRoms = ['hrp2_larm_rom','hrp2_rarm_rom','hrp2_lleg_rom','hrp2_rleg_rom'] +urdfSuffix = "" +srdfSuffix = "" + +rbprmBuilder = Builder () +base_joint_xyz_limits = [-1,3, -1, 1, 0, 6] +rbprmBuilder.loadModel(urdfName, urdfNameRoms, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +rbprmBuilder.setJointBounds ("base_joint_xyz",base_joint_xyz_limits) +#~ rbprmBuilder.setFilter(['hrp2_larm_rom','hrp2_rarm_rom','hrp2_lleg_rom','hrp2_rleg_rom']) +#~ rbprmBuilder.setFilter(['hrp2_lleg_rom','hrp2_rleg_rom']) +#~ rbprmBuilder.setAffordanceFilter('hrp2_rarm_rom', ['Support','Lean']) +#~ rbprmBuilder.setAffordanceFilter('hrp2_larm_rom', ['Support','Lean']) +rbprmBuilder.setAffordanceFilter('hrp2_rarm_rom', ['Support']) +rbprmBuilder.setAffordanceFilter('hrp2_larm_rom', ['Support']) +#~ rbprmBuilder.setAffordanceFilter('hrp2_rarm_rom', ['Lean']) +#~ rbprmBuilder.setAffordanceFilter('hrp2_larm_rom', ['Lean']) +rbprmBuilder.setAffordanceFilter('hrp2_lleg_rom', ['Support',]) +rbprmBuilder.setAffordanceFilter('hrp2_rleg_rom', ['Support']) +#~ rbprmBuilder.setNormalFilter('hrp2_rarm_rom', [0,0,1], 0.5) +#~ rbprmBuilder.setNormalFilter('hrp2_lleg_rom', [0,0,1], 0.9) +#~ rbprmBuilder.setNormalFilter('hrp2_rleg_rom', [0,0,1], 0.9) +#~ rbprmBuilder.setNormalFilter('hyq_rhleg_rom', [0,0,1], 0.9) +rbprmBuilder.boundSO3([-0.,0,-1,1,-1,1]) + +#~ from hpp.corbaserver.rbprm. import ProblemSolver +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver + +ps = ProblemSolver( rbprmBuilder ) + +r = Viewer (ps) + + +q_init = rbprmBuilder.getCurrentConfig (); +q_init [3:7] = [ 0.98877108, 0. , 0.14943813, 0. ] +q_init [0:3] = [-0.05, -0.82, 0.50]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +#~ q_init [0:3] = [0.1, -0.82, 0.648702]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +#~ q_init [0:3] = [0, -0.63, 0.6]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +#~ q_init [3:7] = [ 0.98877108, 0. , 0.14943813, 0. ] + +q_goal = q_init [::] +q_goal [3:7] = [ 0.98877108, 0. , 0.14943813, 0. ] +q_goal [0:3] = [0.6 , -0.82, 1.5]; r (q_goal) +#~ q_goal [0:3] = [3, -0.82, 6]; r(q_goal) +#~ q_goal [0:3] = [1.2, -0.65, 1.1]; r (q_goal) + +#~ ps.addPathOptimizer("GradientBased") +ps.addPathOptimizer("RandomShortcut") +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) + +from hpp.corbaserver.affordance.affordance import AffordanceTool +afftool = AffordanceTool () +afftool.setAffordanceConfig('Support', [0.5, 0.03, 0.00005]) +afftool.setAffordanceConfig('Lean', [0.5, 0.03, 0.00005]) +afftool.loadObstacleModel (packageName, "scale", "planning", r) +#~ afftool.analyseAll() +afftool.visualiseAffordances('Support', r, [0.25, 0.5, 0.5]) +afftool.visualiseAffordances('Lean', r, [0, 0, 0.9]) + +ps.client.problem.selectConFigurationShooter("RbprmShooter") +ps.client.problem.selectPathValidation("RbprmPathValidation",0.05) +#~ ps.solve () +t = ps.solve () + +print t; +if isinstance(t, list): + t = t[0]* 3600000 + t[1] * 60000 + t[2] * 1000 + t[3] +f = open('log.txt', 'a') +f.write("path computation " + str(t) + "\n") +f.close() + + +from hpp.gepetto import PathPlayer +pp = PathPlayer (rbprmBuilder.client.basic, r) +#~ pp.fromFile("/home/stonneau/dev/hpp/src/hpp-rbprm-corba/script/paths/stair.path") +#~ +#~ pp (2) +#~ pp (0) + +#~ pp (1) +#~ pp.toFile(1, "/home/stonneau/dev/hpp/src/hpp-rbprm-corba/script/paths/stair.path") +#~ rbprmBuilder.exportPath (r, ps.client.problem, 1, 0.01, "stair_bauzil_hrp2_path.txt") + +cl = Client() +cl.problem.selectProblem("rbprm_path") +rbprmBuilder2 = Robot ("toto") +ps2 = ProblemSolver( rbprmBuilder2 ) +cl.problem.selectProblem("default") +cl.problem.movePathToProblem(1,"rbprm_path",rbprmBuilder.getAllJointNames()) +r2 = Viewer (ps2, viewerClient=r.client) +r.client.gui.setVisibility("toto", "OFF") +#~ r.client.gui.setVisibility("hrp2_trunk_flexible", "OFF") +#~ r2(q_far) diff --git a/script/scenarios/demos/siggraph_asia/spiderman/scale_spidey_interp.py b/script/scenarios/demos/siggraph_asia/spiderman/scale_spidey_interp.py new file mode 100644 index 0000000..9b94d19 --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/spiderman/scale_spidey_interp.py @@ -0,0 +1,106 @@ +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.corbaserver.rbprm.rbprmfullbody import FullBody +from hpp.gepetto import Viewer +from hpp.gepetto import PathPlayer + +import scale_spidey_path as path_planner +#~ import hrp2_model as model +import time +tp = path_planner + + + +packageName = 'hpp-rbprm-corba' +meshPackageName = 'hpp-rbprm-corba' +rootJointType = "freeflyer" +## +# Information to retrieve urdf and srdf files. +urdfName = "spiderman" +urdfSuffix = "" +srdfSuffix = "" +#~ V0list = tp.V0list +#~ Vimplist = tp.Vimplist +base_joint_xyz_limits = tp.base_joint_xyz_limits + +fullBody = FullBody () +robot = fullBody.client.basic.robot +fullBody.loadFullBodyModel(urdfName, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +fullBody.setJointBounds ("base_joint_xyz", base_joint_xyz_limits) + +#psf = ProblemSolver(fullBody); rr = Viewer (psf); gui = rr.client.gui +ps = path_planner.ProblemSolver( fullBody ) +r = path_planner.Viewer (ps, viewerClient=path_planner.r.client) +rr = r +#~ psf = tp.ProblemSolver( fullBody ); rr = tp.Viewer (psf); gui = rr.client.gui +pp = PathPlayer (fullBody.client.basic, rr); pp.speed = 0.6 +q_0 = fullBody.getCurrentConfig(); rr(q_0) + + +rLegId = 'RFoot' +lLegId = 'LFoot' +rarmId = 'RHand' +larmId = 'LHand' +rfoot = 'SpidermanRFootSphere' +lfoot = 'SpidermanLFootSphere' +lHand = 'SpidermanLHandSphere' +rHand = 'SpidermanRHandSphere' +nbSamples = 50000; x = 0.03; y = 0.08 +fullBody.addLimb(rLegId,'RThigh_rx','SpidermanRFootSphere',[0,0,0],[0,0,1], x, y, nbSamples, "EFORT_Normal", 0.01,"_6_DOF") +fullBody.addLimb(lLegId,'LThigh_rx','SpidermanLFootSphere',[0,0,0],[0,0,1], x, y, nbSamples, "EFORT_Normal", 0.01,"_6_DOF") +fullBody.addLimb(rarmId,'RHumerus_rx','SpidermanRHandSphere',[0,0,0],[0,-1,0], x, y, nbSamples, "EFORT_Normal", 0.01,"_6_DOF") +fullBody.addLimb(larmId,'LHumerus_rx','SpidermanLHandSphere',[0,0,0],[0,1,0], x, y, nbSamples, "EFORT_Normal", 0.01,"_6_DOF") + +fullBody.runLimbSampleAnalysis(rLegId, "jointLimitsDistance", True) +fullBody.runLimbSampleAnalysis(lLegId, "jointLimitsDistance", True) + + + +limbsCOMConstraints = { rLegId : {'file': "spiderman/RL_com.ineq", 'effector' : rfoot}, + lLegId : {'file': "spiderman/LL_com.ineq", 'effector' : rHand}, + rarmId : {'file': "spiderman/RA_com.ineq", 'effector' : rHand}, + larmId : {'file': "spiderman/LA_com.ineq", 'effector' : lHand} } + + +ps = path_planner.ProblemSolver( fullBody ) +r = path_planner.Viewer (ps, viewerClient=path_planner.r.client) +#~ fullBody.setJointBounds ("base_joint_xyz", [-1,3, -1, 1, 0, 2.2]) +fullBody.setJointBounds ("base_joint_xyz", [-1,3, -1, 1, 0, 6]) +pp = PathPlayer (fullBody.client.basic, r) + +from plan_execute import a, b, c, d, e, init_plan_execute +init_plan_execute(fullBody, r, path_planner, pp) + +q_0 = fullBody.getCurrentConfig(); +q_init = fullBody.getCurrentConfig(); q_init[0:7] = path_planner.q_init[0:7] +q_goal = fullBody.getCurrentConfig(); q_goal[0:7] = path_planner.q_goal[0:7] + + +#~ fullBody.setCurrentConfig (q_init) +#~ q_init = [ + #~ -0.05, -0.82, 0.55, 1.0, 0.0 , 0.0, 0.0, # Free flyer 0-6 + #~ 0.0, 0.0, 0.0, 0.0, # CHEST HEAD 7-10 + #~ 0.261799388, 0.174532925, 0.0, -0.523598776, 0.0, 0.0, 0.17, # LARM 11-17 + #~ 0.261799388, -0.174532925, 0.0, -0.523598776, 0.0, 0.0, 0.17, # RARM 18-24 + #~ 0.0, 0.0, -0.453785606, 0.872664626, -0.41887902, 0.0, # LLEG 25-30 + #~ 0.0, 0.0, -0.453785606, 0.872664626, -0.41887902, 0.0, # RLEG 31-36 + #~ ]; r (q_init) + +fullBody.setCurrentConfig (q_goal) +q_goal = fullBody.generateContacts(q_goal, [0,0,1]) +q_init = fullBody.generateContacts(q_init, [0,0,1]) + +#~ fullBody.setStartState(q_init,[rLegId,lLegId,rarmId]) #,rarmId,larmId]) +#~ fullBody.setStartState(q_init,[rLegId,lLegId,larmId, rarmId]) #,rarmId,larmId]) +fullBody.setStartState(q_init,[rLegId,lLegId]) #,rarmId,larmId]) +fullBody.setEndState(q_goal,[rLegId,lLegId])#,rarmId,larmId]) + +configs = d(0.005); e() + +from bezier_traj import * +init_bezier_traj(fullBody, r, pp, configs, limbsCOMConstraints) +#~ AFTER loading obstacles + + +#~ test_ineq(0,{ rLegId : {'file': "hrp2/RL_com.ineq", 'effector' : 'RLEG_JOINT5'}}, 1000, [1,0,0,1]) +#~ test_ineq(0,{ lLegId : {'file': "hrp2/LL_com.ineq", 'effector' : 'LLEG_JOINT5'}}, 1000, [0,0,1,1]) +#~ gen(0,1) diff --git a/script/scenarios/demos/siggraph_asia/spiderman/scale_spidey_path.py b/script/scenarios/demos/siggraph_asia/spiderman/scale_spidey_path.py new file mode 100644 index 0000000..814fffe --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/spiderman/scale_spidey_path.py @@ -0,0 +1,116 @@ +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.gepetto import Viewer +from hpp.corbaserver import Client +from hpp.corbaserver.robot import Robot as Parent + +class Robot (Parent): + rootJointType = 'freeflyer' + packageName = 'hpp-rbprm-corba' + meshPackageName = 'hpp-rbprm-corba' + # URDF file describing the trunk of the robot HyQ + urdfName = 'hrp2_trunk_flexible' + urdfSuffix = "" + srdfSuffix = "" + def __init__ (self, robotName, load = True): + Parent.__init__ (self, robotName, self.rootJointType, load) + self.tf_root = "base_footprint" + self.client.basic = Client () + self.load = load + +rootJointType = 'freeflyer' +packageName = 'hpp-rbprm-corba' +meshPackageName = 'hpp-rbprm-corba' +urdfName = 'spiderman_trunk' +urdfNameRoms = ['SpidermanLFootSphere','SpidermanRFootSphere','SpidermanLHandSphere','SpidermanRHandSphere'] +urdfSuffix = "" +srdfSuffix = "" +ecsSize = 4 +base_joint_xyz_limits = [-10, 10, -10, 15, 0, 10] + +rbprmBuilder = Builder () # RBPRM +rbprmBuilder.loadModel(urdfName, urdfNameRoms, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +rbprmBuilder.setJointBounds ("base_joint_xyz", [-1,3, -1, 1, 0, 6]) +rbprmBuilder.boundSO3([-0.,0,-1,1,-1,1]) +rbprmBuilder.setFilter(urdfNameRoms) +affordanceType = ['Support'] +affordanceTypeHand = ['Support','Lean'] +rbprmBuilder.setAffordanceFilter('SpidermanLFootSphere', affordanceType) +rbprmBuilder.setAffordanceFilter('SpidermanRFootSphere', affordanceType) +rbprmBuilder.setAffordanceFilter('SpidermanLHandSphere', affordanceType) +rbprmBuilder.setAffordanceFilter('SpidermanRHandSphere', affordanceType) +#~ rbprmBuilder.setContactSize (0.03,0.08) +#~ rbprmBuilder.client.basic.robot.setDimensionExtraConfigSpace(ecsSize) +#~ rbprmBuilder.client.basic.robot.setExtraConfigSpaceBounds([0,0,0,0,0,0,-3.14,3.14]) +#~ +#~ rbprmBuilder.boundSO3([-0.,0,-1,1,-1,1]) + +#~ from hpp.corbaserver.rbprm. import ProblemSolver +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver + +ps = ProblemSolver( rbprmBuilder ) + +r = Viewer (ps) + + +q_init = rbprmBuilder.getCurrentConfig (); +q_init [3:7] = [ 0.98877108, 0. , 0.14943813, 0. ] +q_init [0:3] = [0.19999999999999996, -0.82, 1.0]; +rbprmBuilder.setCurrentConfig (q_init); r (q_init) +#~ q_init [0:3] = [0.1, -0.82, 0.648702]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +#~ q_init [0:3] = [0, -0.63, 0.6]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +#~ q_init [3:7] = [ 0.98877108, 0. , 0.14943813, 0. ] + +q_goal = q_init [::] +q_goal [3:7] = [ 0.98877108, 0. , 0.14943813, 0. ] +q_goal [0:3] = [0.6 , -0.82, 1.5]; r (q_goal) +#~ q_goal [0:3] = [3, -0.82, 6]; r(q_goal) +#~ q_goal [0:3] = [1.2, -0.65, 1.1]; r (q_goal) + +#~ ps.addPathOptimizer("GradientBased") +ps.addPathOptimizer("RandomShortcut") +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) + +from hpp.corbaserver.affordance.affordance import AffordanceTool +afftool = AffordanceTool () +afftool.setAffordanceConfig('Support', [0.5, 0.03, 0.00005]) +afftool.setAffordanceConfig('Lean', [0.5, 0.03, 0.00005]) +afftool.loadObstacleModel (packageName, "scale_spidey", "planning", r) +#~ afftool.analyseAll() +afftool.visualiseAffordances('Support', r, [0.25, 0.5, 0.5]) +afftool.visualiseAffordances('Lean', r, [0, 0, 0.9]) + +#~ ps.client.problem.selectConFigurationShooter("RbprmShooter") +#~ ps.client.problem.selectPathValidation("RbprmPathValidation",0.05) +#~ ps.solve () +t = ps.solve () + +print t; +if isinstance(t, list): + t = t[0]* 3600000 + t[1] * 60000 + t[2] * 1000 + t[3] +f = open('log.txt', 'a') +f.write("path computation " + str(t) + "\n") +f.close() + + +from hpp.gepetto import PathPlayer +pp = PathPlayer (rbprmBuilder.client.basic, r) +#~ pp.fromFile("/home/stonneau/dev/hpp/src/hpp-rbprm-corba/script/paths/stair.path") +#~ +#~ pp (2) +#~ pp (0) + +#~ pp (1) +#~ pp.toFile(1, "/home/stonneau/dev/hpp/src/hpp-rbprm-corba/script/paths/stair.path") +#~ rbprmBuilder.exportPath (r, ps.client.problem, 1, 0.01, "stair_bauzil_hrp2_path.txt") + +cl = Client() +cl.problem.selectProblem("rbprm_path") +rbprmBuilder2 = Robot ("toto") +ps2 = ProblemSolver( rbprmBuilder2 ) +cl.problem.selectProblem("default") +cl.problem.movePathToProblem(1,"rbprm_path",rbprmBuilder.getAllJointNames()) +r2 = Viewer (ps2, viewerClient=r.client) +r.client.gui.setVisibility("toto", "OFF") +r.client.gui.setVisibility("spiderman_trunk", "OFF") +#~ r2(q_far) diff --git a/script/scenarios/demos/siggraph_asia/spiderman/spiderman_backJump_interp.py b/script/scenarios/demos/siggraph_asia/spiderman/spiderman_backJump_interp.py new file mode 100644 index 0000000..986ef45 --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/spiderman/spiderman_backJump_interp.py @@ -0,0 +1,69 @@ +#/usr/bin/env python +# author: Mylene Campana (mcampana@laas.fr) +# Script which goes with hpp-rbprm-corba package. + +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.corbaserver.rbprm.rbprmfullbody import FullBody +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver +from hpp.gepetto import Viewer, PathPlayer +import numpy as np +from viewer_library import * + +import spiderman_backJump_path as tp + + +packageName = 'hpp-rbprm-corba' +meshPackageName = 'hpp-rbprm-corba' +rootJointType = "freeflyer" +## +# Information to retrieve urdf and srdf files. +urdfName = "spiderman" +urdfSuffix = "" +srdfSuffix = "" +V0list = tp.V0list +Vimplist = tp.Vimplist +base_joint_xyz_limits = tp.base_joint_xyz_limits + +fullBody = FullBody () +robot = fullBody.client.basic.robot +fullBody.loadFullBodyModel(urdfName, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +fullBody.setJointBounds ("base_joint_xyz", base_joint_xyz_limits) + +#psf = ProblemSolver(fullBody); rr = Viewer (psf); gui = rr.client.gui +r = tp.r; ps = tp.ps +psf = tp.ProblemSolver( fullBody ); rr = tp.Viewer (psf); gui = rr.client.gui +pp = PathPlayer (fullBody.client.basic, rr); pp.speed = 0.6 +q_0 = fullBody.getCurrentConfig(); rr(q_0) + + +flexion = [0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0, 0.2, 0, -0.0, -0.3, 0, 0.2, 0.9, 0, -0.6, 0, 0, 0, -0.2, 0.9, 0, -0.6, 0, 0, 0, -1.1, -1.8, -1, 2.2, -0.9, 0, 0.0, 1.1, -1.8, 1, 2.2, -0.9, 0, 0.0] +q_contact_takeoff = [0, 0, 0, 1, 0, 0, 0, 0, 0.0, 0, -0.0, 0.0, 0.0, 2.2, 0.1, 0.3, -1.5, 0.8, 0, 0, -2.2, 0.1, -0.3, -1.5, -0.8, 0, 0, 0.3, -1.1, 0.2, 2, -0.8, 0, 0.0, -0.3, -1.1, -0.2, 2, -0.8, 0, 0.0] +extending = [0, 0, 0, 1, 0, 0, 0, -0.0, 0.8, 0, -0.0, -0.6, 0, 1.5, 0.5, 1, 0, 0, 0, 0, -1.5, 0.5, -1, 0, 0, 0, 0, 1.4, -1.2, 1.6, 2.1, 0.4, 0, 0.0, -1.4, -1.2, -1.6, 2.1, 0.4, 0.0, 0.0] + +fullBody.setPose (extending, "extending") +fullBody.setPose (flexion, "flexion") +fullBody.setPose (q_contact_takeoff, "takeoffContact") + +rLegId = 'RFoot' +lLegId = 'LFoot' +rarmId = 'RHand' +larmId = 'LHand' +nbSamples = 50000; x = 0.03; y = 0.08 +fullBody.addLimb(rLegId,'RThigh_rx','SpidermanRFootSphere',[0,0,0],[0,0,1], x, y, nbSamples, "EFORT_Normal", 0.01,"_6_DOF") +fullBody.addLimb(lLegId,'LThigh_rx','SpidermanLFootSphere',[0,0,0],[0,0,1], x, y, nbSamples, "EFORT_Normal", 0.01,"_6_DOF") +fullBody.addLimb(rarmId,'RHumerus_rx','SpidermanRHandSphere',[0,0,0],[0,-1,0], x, y, nbSamples, "EFORT_Normal", 0.01,"_6_DOF") +fullBody.addLimb(larmId,'LHumerus_rx','SpidermanLHandSphere',[0,0,0],[0,1,0], x, y, nbSamples, "EFORT_Normal", 0.01,"_6_DOF") +print("Limbs added to fullbody") + + +confsize = len(tp.q11) + +### TEST OF CONTACT CREATION FOR INTERMEDIATE CONFIG, NOT USED FOR INTERPOLATION +q_tmp = q_contact_takeoff [::]; q_tmp[0:confsize-tp.ecsSize] = tp.q_cube[0:confsize-tp.ecsSize]; rr(q_tmp) +fullBody.setCurrentConfig (q_tmp) +q_tmp_test = fullBody.generateContacts(q_tmp, [0,-1,0], True); rr (q_tmp_test) +fullBody.isConfigValid(q_tmp_test) + +# result: +# q_tmp_test = [-1.2, -2.8, 3.6, 0.707107, 0.0, 0.0, 0.707107, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.9324800803082636, -0.9184709614284768, 0.6886200849241174, -0.6066622060535428, 0.47649495495305294, 1.0976823065116303, -0.538404483799899, -1.0681738092891575, -1.1021076588270258, 1.1498838725595328, -0.6156809000975677, 0.5815958533218022, -1.4659758542959642, -0.3603605133380307, 0.36116581520970376, -1.048638878548546, 0.24059108997189355, 1.23953255675232, -0.7519812787252685, -0.1402404928640359, -1.0, 0.023118656707620415, -0.6298340889273957, -0.15800407650545129, 0.4963824557225752, -0.4989080182494368, 0.2774303858753873, -0.9974339561414656] + diff --git a/script/scenarios/demos/siggraph_asia/spiderman/spiderman_backJump_path.py b/script/scenarios/demos/siggraph_asia/spiderman/spiderman_backJump_path.py new file mode 100644 index 0000000..d135480 --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/spiderman/spiderman_backJump_path.py @@ -0,0 +1,107 @@ +#/usr/bin/env python +# author: Mylene Campana (mcampana@laas.fr) +# Script which goes with hpp-rbprm-corba package. +# The script launches a skeleton-robot and a groundcrouch environment. +# It defines init and final configs, and solve them with RBPRM. +# Range Of Motions are spheres linked to the 4 end-effectors + +from hpp.corbaserver import Client +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver +from hpp.corbaserver.rbprm.rbprmbuilder import Builder +from hpp.gepetto import Viewer, PathPlayer +import math +from viewer_library import * + +rootJointType = 'freeflyer' +packageName = 'hpp-rbprm-corba' +meshPackageName = 'hpp-rbprm-corba' +urdfName = 'spiderman_trunk' +urdfNameRoms = ['SpidermanLFootSphere','SpidermanRFootSphere','SpidermanLHandSphere','SpidermanRHandSphere'] +urdfSuffix = "" +srdfSuffix = "" +ecsSize = 4 +base_joint_xyz_limits = [-10, 10, -10, 15, 0, 10] + +rbprmBuilder = Builder () # RBPRM +rbprmBuilder.loadModel(urdfName, urdfNameRoms, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +rbprmBuilder.setJointBounds ("base_joint_xyz", base_joint_xyz_limits) +rbprmBuilder.boundSO3([-0.2,0.2,-3.14,3.14,-0.3,0.3]) +rbprmBuilder.setFilter(urdfNameRoms) +affordanceType = ['Support'] +rbprmBuilder.setAffordanceFilter('SpidermanLFootSphere', affordanceType) +rbprmBuilder.setAffordanceFilter('SpidermanRFootSphere', affordanceType) +rbprmBuilder.setAffordanceFilter('SpidermanLHandSphere', affordanceType) +rbprmBuilder.setAffordanceFilter('SpidermanRHandSphere', affordanceType) +rbprmBuilder.setContactSize (0.03,0.08) +rbprmBuilder.client.basic.robot.setDimensionExtraConfigSpace(ecsSize) +rbprmBuilder.client.basic.robot.setExtraConfigSpaceBounds([0,0,0,0,0,0,-3.14,3.14]) + +#~ from hpp.corbaserver.rbprm. import ProblemSolver +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver + +ps = ProblemSolver( rbprmBuilder ) + +r = Viewer (ps) + + +q_init = rbprmBuilder.getCurrentConfig (); +q_init [3:7] = [ 0.98877108, 0. , 0.14943813, 0. ] +q_init [0:3] = [-0.05, -0.82, 0.50]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +#~ q_init [0:3] = [0.1, -0.82, 0.648702]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +#~ q_init [0:3] = [0, -0.63, 0.6]; rbprmBuilder.setCurrentConfig (q_init); r (q_init) +#~ q_init [3:7] = [ 0.98877108, 0. , 0.14943813, 0. ] + +q_goal = q_init [::] +q_goal [3:7] = [ 0.98877108, 0. , 0.14943813, 0. ] +q_goal [0:3] = [0.6 , -0.82, 1.5]; r (q_goal) +#~ q_goal [0:3] = [3, -0.82, 6]; r(q_goal) +#~ q_goal [0:3] = [1.2, -0.65, 1.1]; r (q_goal) + +#~ ps.addPathOptimizer("GradientBased") +ps.addPathOptimizer("RandomShortcut") +ps.setInitialConfig (q_init) +ps.addGoalConfig (q_goal) + +from hpp.corbaserver.affordance.affordance import AffordanceTool +afftool = AffordanceTool () +afftool.setAffordanceConfig('Support', [0.5, 0.03, 0.00005]) +afftool.setAffordanceConfig('Lean', [0.5, 0.03, 0.00005]) +afftool.loadObstacleModel (packageName, "scale", "planning", r) +#~ afftool.analyseAll() +afftool.visualiseAffordances('Support', r, [0.25, 0.5, 0.5]) +afftool.visualiseAffordances('Lean', r, [0, 0, 0.9]) + +ps.client.problem.selectConFigurationShooter("RbprmShooter") +ps.client.problem.selectPathValidation("RbprmPathValidation",0.05) +#~ ps.solve () +t = ps.solve () + +print t; +if isinstance(t, list): + t = t[0]* 3600000 + t[1] * 60000 + t[2] * 1000 + t[3] +f = open('log.txt', 'a') +f.write("path computation " + str(t) + "\n") +f.close() + + +from hpp.gepetto import PathPlayer +pp = PathPlayer (rbprmBuilder.client.basic, r) +#~ pp.fromFile("/home/stonneau/dev/hpp/src/hpp-rbprm-corba/script/paths/stair.path") +#~ +#~ pp (2) +#~ pp (0) + +#~ pp (1) +#~ pp.toFile(1, "/home/stonneau/dev/hpp/src/hpp-rbprm-corba/script/paths/stair.path") +#~ rbprmBuilder.exportPath (r, ps.client.problem, 1, 0.01, "stair_bauzil_hrp2_path.txt") + +cl = Client() +cl.problem.selectProblem("rbprm_path") +rbprmBuilder2 = Robot ("toto") +ps2 = ProblemSolver( rbprmBuilder2 ) +cl.problem.selectProblem("default") +cl.problem.movePathToProblem(1,"rbprm_path",rbprmBuilder.getAllJointNames()) +r2 = Viewer (ps2, viewerClient=r.client) +r.client.gui.setVisibility("toto", "OFF") +#~ r.client.gui.setVisibility("hrp2_trunk_flexible", "OFF") +#~ r2(q_far) diff --git a/script/scenarios/demos/siggraph_asia/spiderman/spiderman_compute_DB.py b/script/scenarios/demos/siggraph_asia/spiderman/spiderman_compute_DB.py new file mode 100644 index 0000000..3397eb7 --- /dev/null +++ b/script/scenarios/demos/siggraph_asia/spiderman/spiderman_compute_DB.py @@ -0,0 +1,121 @@ +#/usr/bin/env python +# author: Mylene Campana (mcampana@laas.fr) +# Script which goes with hpp-rbprm-corba package. + +from hpp.corbaserver.rbprm.rbprmbuilder import Builder + +from hpp.corbaserver.rbprm.rbprmfullbody import FullBody +from hpp.corbaserver.rbprm.tools.plot_analytics import plotOctreeValues +from hpp.corbaserver.rbprm.problem_solver import ProblemSolver +import numpy as np +from viewer_library import * + + + +packageName = 'hpp-rbprm-corba' +meshPackageName = 'hpp-rbprm-corba' +rootJointType = "freeflyer" +## +# Information to retrieve urdf and srdf files. +urdfName = "spiderman" +urdfSuffix = "" +srdfSuffix = "" + + +fullBody = FullBody () + +fullBody.loadFullBodyModel(urdfName, rootJointType, meshPackageName, packageName, urdfSuffix, srdfSuffix) +fullBody.setJointBounds ("base_joint_xyz", [0,0,0,0,0,0]) + +""" +from hpp.gepetto import Viewer +psf = ProblemSolver( fullBody ); rr = Viewer (psf) +q_0 = fullBody.getCurrentConfig(); rr(q_0); fullBody.isConfigValid(q_0) +""" + + +q_flexion = [0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0, 0.2, 0, -0.0, -0.3, 0, 0.2, 0.9, 0, -0.6, 0, 0, 0, -0.2, 0.9, 0, -0.6, 0, 0, 0, -1.1, -1.8, -1, 2.2, -0.9, 0, 0.0, 1.1, -1.8, 1, 2.2, -0.9, 0, 0.0] +q_contact = [0, 0, 0, 1, 0, 0, 0, 0, 0.0, 0, -0.0, 0.0, 0.0, 2.2, 0.1, 0.3, -1.5, 0.8, 0, 0, -2.2, 0.1, -0.3, -1.5, -0.8, 0, 0, 0.3, -1.1, 0.2, 2, -0.8, 0, 0.0, -0.3, -1.1, -0.2, 2, -0.8, 0, 0.0] + +fullBody.isConfigValid(q_flexion) +fullBody.isConfigValid(q_contact) + + + +q_lfeet = q_flexion[fullBody.rankInConfiguration ['LThigh_rx']:fullBody.rankInConfiguration ['LFootToe_ry']+1] +q_rfeet = q_flexion[fullBody.rankInConfiguration ['RThigh_rx']:fullBody.rankInConfiguration ['RFootToe_ry']+1] +q_larm = q_contact[fullBody.rankInConfiguration ['LHumerus_rx']:fullBody.rankInConfiguration ['LHand_ry']+1] +q_rarm = q_contact[fullBody.rankInConfiguration ['RHumerus_rx']:fullBody.rankInConfiguration ['RHand_ry']+1] + +fullBody.addRefConfigAnalysisWeight(q_lfeet,"RefPoseLFeet",[1.,1.,1.,5.,1.,1.,1.]) +fullBody.addRefConfigAnalysisWeight(q_rfeet,"RefPoseRFeet",[1.,1.,1.,5.,1.,1.,1.]) +fullBody.addRefConfigAnalysis(q_larm,"RefPoseLArm") +fullBody.addRefConfigAnalysis(q_rarm,"RefPoseRArm") + + +nbSamples = 50000 +x = 0.03 # contact surface width +y = 0.08 # contact surface length + +rLegId = 'RFoot' +lLegId = 'LFoot' +rarmId = 'RHand' +larmId = 'LHand' + +fullBody.addLimb(rLegId,'RThigh_rx','SpidermanRFootSphere',[0,0,0],[0,0,1], x, y, nbSamples, "EFORT_Normal", 0.01,"_3_DOF") +fullBody.addLimb(lLegId,'LThigh_rx','SpidermanLFootSphere',[0,0,0],[0,0,1], x, y, nbSamples, "EFORT_Normal", 0.01,"_3_DOF") + +fullBody.addLimb(rarmId,'RHumerus_rx','SpidermanRHandSphere',[0,0,0],[0,-1,0], x, y, nbSamples, "EFORT_Normal", 0.01,"_6_DOF") +fullBody.addLimb(larmId,'LHumerus_rx','SpidermanLHandSphere',[0,0,0],[0,1,0], x, y, nbSamples, "EFORT_Normal", 0.01,"_6_DOF") + +print("Limbs added to fullbody") + +def runallLLeg(lid, dbName): + fullBody.runLimbSampleAnalysis(lid, "minimumSingularValue", False) + fullBody.runLimbSampleAnalysis(lid, "manipulabilityTr", False) + fullBody.runLimbSampleAnalysis(lid, "jointLimitsDistance", False) + fullBody.runLimbSampleAnalysis(lid, "isotropyTr", False) + fullBody.runLimbSampleAnalysis(lid, "isotropy", False) + fullBody.runLimbSampleAnalysis(lid, "manipulability", False) + fullBody.runLimbSampleAnalysis(lid, "RefPoseLFeet", True) + fullBody.saveLimbDatabase(lid, dbName) + +def runallRLeg(lid, dbName): + fullBody.runLimbSampleAnalysis(lid, "minimumSingularValue", False) + fullBody.runLimbSampleAnalysis(lid, "manipulabilityTr", False) + fullBody.runLimbSampleAnalysis(lid, "jointLimitsDistance", False) + fullBody.runLimbSampleAnalysis(lid, "isotropyTr", False) + fullBody.runLimbSampleAnalysis(lid, "isotropy", False) + fullBody.runLimbSampleAnalysis(lid, "manipulability", False) + fullBody.runLimbSampleAnalysis(lid, "RefPoseRFeet", True) + fullBody.saveLimbDatabase(lid, dbName) + +def runallLArm(lid, dbName): + fullBody.runLimbSampleAnalysis(lid, "minimumSingularValue", False) + fullBody.runLimbSampleAnalysis(lid, "manipulabilityTr", False) + fullBody.runLimbSampleAnalysis(lid, "jointLimitsDistance", False) + fullBody.runLimbSampleAnalysis(lid, "isotropyTr", False) + fullBody.runLimbSampleAnalysis(lid, "isotropy", False) + fullBody.runLimbSampleAnalysis(lid, "manipulability", False) + fullBody.runLimbSampleAnalysis(lid, "RefPoseLArm", True) + fullBody.saveLimbDatabase(lid, dbName) + +def runallRArm(lid, dbName): + fullBody.runLimbSampleAnalysis(lid, "minimumSingularValue", False) + fullBody.runLimbSampleAnalysis(lid, "manipulabilityTr", False) + fullBody.runLimbSampleAnalysis(lid, "jointLimitsDistance", False) + fullBody.runLimbSampleAnalysis(lid, "isotropyTr", False) + fullBody.runLimbSampleAnalysis(lid, "isotropy", False) + fullBody.runLimbSampleAnalysis(lid, "manipulability", False) + fullBody.runLimbSampleAnalysis(lid, "RefPoseRArm", True) + fullBody.saveLimbDatabase(lid, dbName) + + + +print("Run all legs : ") +runallLLeg(lLegId, './Spiderman_lleg_flexion_3DOF_EN.db') +runallRLeg(rLegId, './Spiderman_rleg_flexion_3DOF_EN.db') +print("Run all arms : ") +#runallLArm(larmId, './Spiderman_larm_contact_6DOF_EN.db') +#runallRArm(rarmId, './Spiderman_rarm_contact_6DOF_EN.db') + -- GitLab