From 7d2a505f3fe0b788dc851cad65b6ff2385a796aa Mon Sep 17 00:00:00 2001 From: m-guberina <gubi.guberina@gmail.com> Date: Fri, 11 Oct 2024 11:53:47 +0200 Subject: [PATCH] bugfix --- Dockerfile | 3 +- python/examples/drawing_from_input_drawing.py | 4 +- python/examples/path_in_pixels.csv | 180 ++++++++---------- python/examples/point_impedance_control.py | 2 +- .../__pycache__/managers.cpython-312.pyc | Bin 36916 -> 36949 bytes .../basics/__pycache__/basics.cpython-312.pyc | Bin 1897 -> 2183 bytes .../clik_trajectory_following.cpython-312.pyc | Bin 3739 -> 5762 bytes .../clik/clik_trajectory_following.py | 2 +- python/ur_simple_control/managers.py | 7 +- 9 files changed, 85 insertions(+), 113 deletions(-) diff --git a/Dockerfile b/Dockerfile index 7c95f8c..209a5ac 100644 --- a/Dockerfile +++ b/Dockerfile @@ -14,7 +14,8 @@ RUN apt install -y \ git \ sudo \ man-db \ - manpages-posix + manpages-posix \ + arp-scan RUN sed -i 's:^path-exclude=/usr/share/man:#path-exclude=/usr/share/man:' \ /etc/dpkg/dpkg.cfg.d/excludes diff --git a/python/examples/drawing_from_input_drawing.py b/python/examples/drawing_from_input_drawing.py index b9cbfb7..1231415 100644 --- a/python/examples/drawing_from_input_drawing.py +++ b/python/examples/drawing_from_input_drawing.py @@ -42,7 +42,7 @@ def getArgs(): parser.add_argument('--robot-ip', type=str, help="robot's ip address (only needed if running on the real robot)", \ default="192.168.1.102") - parser.add_argument('--pinocchio-only', action=argparse.BooleanOptionalAction, + parser.add_argument('--pinocchio-only', action=argparse.BooleanOptionalAction, \ help="whether you want to just integrate with pinocchio.\ NOTE: doesn't actually work because it's not a physics simulator", \ default=False) @@ -78,7 +78,7 @@ def getArgs(): help="the final position error you are happy with. NOTE: not used here", \ default=1e-3) parser.add_argument("--start-from-current-pose", action=argparse.BooleanOptionalAction, \ - help="if connected to the robot, read the current pose and set it as the initial pose for the robot. + help="if connected to the robot, read the current pose and set it as the initial pose for the robot.\ very useful and convenient when running simulation before running on real", \ default=False) parser.add_argument('--tikhonov-damp', type=float, \ diff --git a/python/examples/path_in_pixels.csv b/python/examples/path_in_pixels.csv index d91143f..bc9ca0b 100644 --- a/python/examples/path_in_pixels.csv +++ b/python/examples/path_in_pixels.csv @@ -1,105 +1,75 @@ -0.44544,0.71519 -0.44544,0.71519 -0.44544,0.71390 -0.43938,0.71002 -0.43533,0.70614 -0.42724,0.70098 -0.41915,0.69581 -0.38882,0.67125 -0.37466,0.66350 -0.35848,0.65187 -0.34837,0.64282 -0.30792,0.60535 -0.29578,0.59114 -0.27556,0.57434 -0.24118,0.53557 -0.23106,0.52652 -0.22904,0.52265 -0.22500,0.51360 -0.22500,0.51231 -0.22500,0.51231 -0.22500,0.51102 -0.22702,0.50972 -0.23511,0.50456 -0.24320,0.49939 -0.28365,0.49034 -0.29376,0.48776 -0.30792,0.48517 -0.34432,0.48129 -0.36859,0.47742 -0.38882,0.47742 -0.44140,0.47742 -0.45353,0.48000 -0.48792,0.48905 -0.50814,0.49551 -0.66589,0.53428 -0.70836,0.54720 -0.76297,0.56271 -0.87016,0.59760 -0.89645,0.60923 -0.90050,0.61181 -0.90252,0.61310 -0.90252,0.61181 -0.90252,0.61310 -0.90252,0.61440 -0.89847,0.61440 -0.88836,0.61956 -0.88432,0.62086 -0.87016,0.62732 -0.86207,0.62990 -0.82364,0.64282 -0.80949,0.64541 -0.76701,0.65445 -0.74274,0.65833 -0.73061,0.66092 -0.67196,0.66609 -0.64971,0.66996 -0.63960,0.66996 -0.62949,0.67255 -0.60724,0.67513 -0.56275,0.68547 -0.54859,0.68547 -0.50410,0.69968 -0.49803,0.70098 -0.48387,0.70485 -0.48185,0.70485 -0.47174,0.70744 -0.46971,0.70744 -0.46769,0.70744 -0.46567,0.70744 -0.46365,0.70744 -0.45758,0.70744 -0.43938,0.70744 -0.38275,0.70098 -0.36859,0.70098 -0.35848,0.69968 -0.33623,0.69968 -0.33623,0.69839 -0.33421,0.69839 -0.33421,0.69710 -0.33421,0.69581 -0.33623,0.69193 -0.34028,0.68805 -0.35039,0.67772 -0.35241,0.67513 -0.36252,0.66479 -0.40095,0.61569 -0.41511,0.60406 -0.45556,0.54591 -0.46769,0.53169 -0.47780,0.51748 -0.51825,0.45803 -0.53039,0.44382 -0.54050,0.43477 -0.55263,0.41927 -0.56072,0.40764 -0.59713,0.36112 -0.60724,0.35207 -0.62949,0.32881 -0.63151,0.32493 -0.63151,0.32364 -0.63555,0.31976 -0.63555,0.31847 -0.63758,0.31847 -0.63758,0.31847 -0.63758,0.31847 +0.51607,0.68193 +0.51829,0.68193 +0.51829,0.68193 +0.52052,0.68041 +0.52052,0.68041 +0.52052,0.67889 +0.52496,0.67738 +0.52718,0.67586 +0.52940,0.67434 +0.53828,0.66826 +0.54050,0.66674 +0.54272,0.66522 +0.54494,0.66370 +0.55605,0.65155 +0.55827,0.65003 +0.56715,0.64396 +0.56715,0.64244 +0.56715,0.64244 +0.56715,0.64092 +0.56715,0.63940 +0.56715,0.63788 +0.56715,0.63636 +0.56715,0.63636 +0.56715,0.63029 +0.55827,0.62117 +0.55827,0.61966 +0.54939,0.61358 +0.52940,0.59080 +0.52496,0.58624 +0.51829,0.58168 +0.48498,0.55890 +0.47388,0.55434 +0.46721,0.55130 +0.44945,0.54371 +0.41836,0.53459 +0.41169,0.53308 +0.40503,0.53308 +0.38726,0.52548 +0.38726,0.52548 +0.38060,0.52548 +0.37394,0.52548 +0.37394,0.52396 +0.37172,0.52396 +0.36950,0.52396 +0.36950,0.52396 +0.36950,0.52548 +0.36950,0.52548 +0.36950,0.53004 +0.37172,0.53156 +0.37616,0.54219 +0.38060,0.54675 +0.38504,0.55586 +0.38948,0.56497 +0.40503,0.59991 +0.40947,0.60447 +0.41836,0.61358 +0.43612,0.64852 +0.43834,0.65307 +0.44278,0.66370 +0.46499,0.68801 +0.46944,0.69712 +0.47388,0.70168 +0.47832,0.71231 +0.49164,0.72598 +0.49831,0.73661 +0.50719,0.74269 +0.51607,0.75332 +0.52052,0.75788 +0.52274,0.75940 +0.52496,0.76092 +0.52496,0.76244 +0.52718,0.76244 +0.52718,0.76396 +0.52718,0.76396 +0.52718,0.76396 diff --git a/python/examples/point_impedance_control.py b/python/examples/point_impedance_control.py index fb58d87..e094873 100644 --- a/python/examples/point_impedance_control.py +++ b/python/examples/point_impedance_control.py @@ -72,7 +72,7 @@ def getArgs(): default=1e-3) # TODO: test the interaction of this and the overall demo parser.add_argument("--start-from-current-pose", action=argparse.BooleanOptionalAction, \ - help="if connected to the robot, read the current pose and set it as the initial pose for the robot. + help="if connected to the robot, read the current pose and set it as the initial pose for the robot. \ very useful and convenient when running simulation before running on real", \ default=False) parser.add_argument('--tikhonov-damp', type=float, \ diff --git a/python/ur_simple_control/__pycache__/managers.cpython-312.pyc b/python/ur_simple_control/__pycache__/managers.cpython-312.pyc index b7c269db67426979fe7f362c0ef01a1ff2715e03..ac78c9ecfbfb2b36f7db8dfd8b9ca6621c026c2d 100644 GIT binary patch delta 335 zcmdn8fa&T2Cf?J$yj%<n3=BD6InqCD<P|e!G}^3Ue1b!IX$@mm97qNg7tJgQoLp_C zIoZHw*W^RSqD)27lO4sxHvhNT%*=Rk^Ja&&%rgAK*ZDOs@oU}?5V<a3cu~Ocx`63L z0n-hMR|G637rV@2JT{rnbv5J3&AVI|FfpFl9PMGj$arV-6we@5#)q4q`_;2EvTjZf zd&|hEyE!!C6bqxpW`$TTcE+g9+9|(S7&|wsWqL6)uHIajbC8j3Cldohaq#50!jR29 zd1sgy4{nYuRAFVju(__xlaZ~Gp@t!gY4S%&;mr@q>lhi|PL8kCVHBF&Q@IvNZt{cj z{>cxkQW?L)rIj{Mt3J-f$htYMt&EM)X7kk^X-2kuMpn^JS)0H0>ND|2aWL9{VgQjv ICJYP=0KUm_9smFU delta 308 zcmcb*fN9GDCf?J$yj%<n3=BU{v#0Of$SY>dD79I|_yh;z%*k)9#hH6c0w-5nX-+n< z*)_RMT6D9x?Pg}i6Pr&vtYsGF5xCBydyz-?I*;K+9>WcaS9nY&PjQ*WcyzM9>uSam zn{T@=U}8MIxyHkSk@5ECt)4-wj1M+*_}8;DvTW`Md&|hEv$-td6bqyIX2)1AcE-rf zJ}JLg7&|t*XL>O+uG%~)=O8274kiYM;^4{kg&~{Q=AB_;Jg~W{P=%H8{O0*(o{Vgq z3^fc{Op`xK3Qu;36rS8xRWo@)#e2p#lN%~^7zHM;tz3(#<RRlXxU|yd?bXM*7+E&g px0SImT5tZ=BhAQ`$H*%BDPyyEpFR_RBnPAYCk7B%WWvC}008$6Z7%=- diff --git a/python/ur_simple_control/basics/__pycache__/basics.cpython-312.pyc b/python/ur_simple_control/basics/__pycache__/basics.cpython-312.pyc index a907dd1917993fe0c168898bc788a4aa7abd34c3..6d6ee6502c796e5009f143ec1dc9030248ebc7b0 100644 GIT binary patch delta 469 zcmaFK*DlC=nwOW0fq{YHX9Zh&=|o;h#)OILo)e2^@G_+^OEJ{4)i9(mr7%wxXY}S} z$!20;C}K)stz}7Jo1D)WT+d$B%%z~9ppctimg?o4pI1_ppW~CCUjP==MFn87-2CDa zg`~vd%w&ZCg=B~Zg|z%4g{=I{yb^`tg2d!hg#r*;w<KQ|%uvY9FUic$(@{uFE-6jS zf$Pf2&*v=A1DopRxA`ce0;2#g0|P^G2Ll5`1H%U%20^jSpP7mo>zOK<G?}Yrf>nYY z3TB}?P8TdjzUv_F$SN%^Q7A4+EGj8hD9K2LI8`w}M<FLazd)fpvm_(Gv_v5>uTmi= zKRrD&FCC(7at@0nqu=DEEK39oKt4zZ```;71CPMuaMpc{PLsvhQW@PQ*RZW)G@7i< iE-(FwMV3+alN%#HqbK7h6-GwR&m4@5oJG<M3=9Cy{e>R@ delta 181 zcmZn{e96aqnwOW0fq{Wx?+NB~@rk^Wj7byKJ()NeCKk-#Wk_L?VyI=SVMt*}VVW$; z=*`QV&BVY^#FWBP%aX!6IhQe*na$5_vj>v`BcBKZ14D5e0|P??!wmt^%@xeWjBE^* z44O=Sle<|hCm&^9!e<0hk_uLGhns(LCEGqmyU7;psf<pO=drJ2G@I<pAus=dg^iKr e6Q2a5>?a#eMo-315{!(TpE(#AIg6wj7#IMg2`M!I diff --git a/python/ur_simple_control/clik/__pycache__/clik_trajectory_following.cpython-312.pyc b/python/ur_simple_control/clik/__pycache__/clik_trajectory_following.cpython-312.pyc index d900eed3d1c0b5d9a5e328f65abf299bf57f1759..d9dbfe9f04563a9582b17f077410172d86db78d4 100644 GIT binary patch delta 2342 zcmbO&+oa2TnwOW0fq{V`;}b{v`H8%ej3yJ+HQ7>_TNt9)Cq``!WJ+ObWlCXAW0GWG zV5niNVr5{cVM&3D+JHo1d`74$CKOeSX-pthDJ&3ulj9i0>mmA~GBqs044SNoUzive zxD*r=6mk;_j9dZ|OEN<8ja>qA67y2Q!n#-hSR%yV#otOH#KY6iTfx!KMZwL}&(X&- z%2gr6!&Sj8$kEpoNm+Q1XNYUPLO_tGUx<RElYeLkLYYE{KbR95>>32tl2}|^np;qk znV(l|1s2d%$S=xF&&*TE%u^`IFVM|NO)F7I&M(SKEmF|PODri(%uz_oFH$H^EiOqd z%2UWmEXmAMC{8ZQEGSVZFUl;*%uCngQm9u@P|#JVP)N^DEmkPXOwTA$&`2xF&s7L< z4$y>JRHaa!nUkZCp0AKto>-{>mM+OiRY=NDEJ}f@sZ_`+Ee1Itw;(6AB(+!pqyTK5 zZbo8Wib7gZVlE``AYl~b>FyDt;OAc-u27z;kdmLLUZRkZSeB}g2yq2iS1MGWLQZaC zzK%k2Mq*xiszOOdVu?a|Mru*2LS~6VaYlY=PKrVj#Be|V5LYXOl8nq^g|yPVWKei1 zBo-@_r{?4+B&CAGDkD{)v?Mb}A-_l=r6{q!JTos{AuTf}RYxJI6l88<NorYY5jgDf z^2>EVc7VN~1a>CG8c^C$P{_|q20H;PotO*?@|;SLHF>G2DXA$6sX4`|V0VJUC@8h0 zv?#AwAyL8DMWG<EBts#wprEKezn~~Hu_QI8QlU6GF()-eM*$RE1v!bysVNGXc_sPa zkW9-gDlSndEKN))O3W((o0p#kmZ{LKR44$YOa-VwQhrLME;zUqG$3JJ4hpbLNR)tN zA(5ewnWj*lDxqGKs*s+Vms*sVV-Jb&my8Sy41SaQ7~cs9GB7X{w=*y>G%$QoV<7 z+{JW=g_$LVb+SKusx(^_7Xw4K1_MJe(*(wzQzanPpbX5A!an&t`$<N&$ul`3l{spJ zQ#ez&)^M+80ZTG4GSmnMGidT8er17Xv&r?`a`j+OVaZrXLSQAZcuma7EU5&GAgRy= z3%KRy<m8uwg1Vq6zbq3J7tV=AC8@=kiFx3l*8wX_E=o-VCDlZQto+RSyb^`tg2d!h zg_5GgtkmR^{Gv*5BFHS!;{q!$0!JX239%8v1ZmDIi3jVAN77r8uaE|I2RNG2Gs{vT zc0)}|EJ`oUP0cGQhM1yT4>400;saf<Ga)%$K|xp7P9Yh^0}2rHKzTp0I2#h7V1uAB zUX)pqs*qS*oLW>;4E9AyMrv`Y0-B{DKD0Pds0Z7Un3Dr`Zf;_FX0k$FX>L+#QL#d4 zacYVJIKw5SmXxFxfzmjL3${^LAvq^A+c`h4q$ocpC$$L0(K(sf3dwLOh06R=P<ksZ z&df`PYA(u8$}h2k6hsi827yF;6Y~<&Q;QTb^NLFnLHSGrnyEl#T3UWld16tDLUv|e zYHnglW^%DYYDqFA^+Ez5H?b0w-AmMq6`)Q|NiEJy2NjhHsTBpO$tB<b1{Da<98sT` zo2rnRk_~niB!7d7u=M==6i|7RmktSl%wm`)((;QySrnW>GxM?)5|i>vOCT{(tOqs) z=9FwunUx7jj@jjjMd=FVnV`(Cke6Col$ZlbZh6IN`SnG)ppq&jH7&6;rvzevE>toe z<i_}t#NzCDaK^S$0Gkg9E=Q=M{31|L<mVxm&nckN8sssME8z(RVmL&%XNdyHWyQty zrMamfpC*=o69Bk?Do-p{faf4kTFXdP0J#F<OQ;(_VU?7coLE|%s$i*aXrNG%nF}ue z6G5S$n_rX)N&#i5d6}tsC6J5<(xLz^=PL6{6_OM46tYU|i$PIR3<@RGfGNral~mA_ zlb2tj08Tv$plk^;M^~XRJ~J;9l!QQBa4Ie?Nh|`@ZwdwZnRz98$e{(ZFgL#}HA|r+ zA5^?2rKaT<MW-sHR-`7Eg7tx79+8!i99;}5jx&oDauc&tixmn|i_$<zsW>&SI2B}A zYF=?E*uO<ZsmUdIsl|}oJ(-77g3)iY3TGV?pB|`4^<e@RseX)`*K_Y;QkP?3VEDky m$jJCvh=Eb~HiP(W2JX8ImY=w!7==GuWic|!6bUgfFaQ8eK)jIv delta 327 zcmZqDoh{3InwOW0fq{YH?d@M_>=St<87(HNYjSZiq%gNIM6q)+Obpvx&yd2<%9O&C z#w5wWz)-_j#mc}?!;%6QwE>C3_>53hOem@t)0jZ2QkdcTpz6S?n5xiB0I98E31-k_ z@q5Y0z{J2XxtZl1pCSVTLvbqu149GD9S*L|jjV@Qm>E)7CcAN^GO|uy!zIbcHu)IW zNk-Pm6SyO#*lUDSI8r#*aIIzm`Hz8tk)cL7m_d`<Z}J}jiOr&dbxgcLAQQcrKqh`+ z+q_VC7n6}D0|UbcW=2NF&q550!nYa3Z!>V;Ww89f#m~s{Nr8(|_=A)(Bg<zGMmI)A KnIa(u1_l7LWko#z diff --git a/python/ur_simple_control/clik/clik_trajectory_following.py b/python/ur_simple_control/clik/clik_trajectory_following.py index eae999f..96908e4 100644 --- a/python/ur_simple_control/clik/clik_trajectory_following.py +++ b/python/ur_simple_control/clik/clik_trajectory_following.py @@ -44,6 +44,7 @@ def map2DPathTo3DPlane(path_2D, width, height): def clikCartesianPathIntoJointPath(path, args, robot, \ + clikController, q_init, R, p): """ clikCartesianPathIntoJointPath ------------------------------ @@ -80,7 +81,6 @@ def clikCartesianPathIntoJointPath(path, args, robot, \ --> you can movej to it before executing the trajectory, so this makes perfect sense to ensure correctness """ - clikController, q_init, R, p): transf_body_to_task_frame = pin.SE3(R, p) q = copy.deepcopy(q_init) diff --git a/python/ur_simple_control/managers.py b/python/ur_simple_control/managers.py index 8249200..b8d1f2d 100644 --- a/python/ur_simple_control/managers.py +++ b/python/ur_simple_control/managers.py @@ -440,7 +440,8 @@ class RobotManager: q.append(0.0) q = np.array(q) self.q = q - self.manipulator_visualizer_queue.put(q) + if args.visualize_manipulator: + self.manipulator_visualizer_queue.put(q) # do it once to get T_w_e @@ -749,7 +750,7 @@ class RobotManager: if self.gripper is None: if self.args.debug_prints: print("you didn't select a gripper (no gripper is the default parameter) so no gripping for you") - pass + return if (not self.args.simulation) and (not self.args.pinocchio_only): self.gripper.open() else: @@ -759,7 +760,7 @@ class RobotManager: if self.gripper is None: if self.args.debug_prints: print("you didn't select a gripper (no gripper is the default parameter) so no gripping for you") - pass + return if (not self.args.simulation) and (not self.args.pinocchio_only): self.gripper.close() else: -- GitLab