From bffc3841ab7eae6e9082bf5b48ceff08fc137503 Mon Sep 17 00:00:00 2001 From: "Ziwei.He" Date: Thu, 29 May 2025 16:47:49 +0800 Subject: [PATCH] =?UTF-8?q?=E8=A7=86=E8=A7=89=E6=A0=87=E5=AE=9A=E5=AE=8C?= =?UTF-8?q?=E6=88=90?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Massage/Massage.pyc | Bin .../__pycache__/dobot_api.cpython-38.pyc | Bin 136685 -> 136688 bytes .../__pycache__/dobot_nova5.cpython-39.pyc | Bin 23743 -> 23567 bytes .../__pycache__/remote_cam.cpython-39.pyc | Bin 0 -> 5518 bytes Massage/MassageControl/hardware/capture.py | 124 +++++++++ .../MassageControl/hardware/dobot_nova5.py | 26 +- Massage/MassageControl/hardware/remote_cam.py | 235 ++++++++++++++++++ .../tools/auto_visual_valibration.py | 106 ++++---- Massage/controller.service | 0 Massage/test_manual.py | 0 Massage/test_manual.pyc | Bin Massage/tools/__pycache__/log.cpython-38.pyc | Bin 0 -> 3223 bytes Restart_Speaker.py | 0 Restart_Speaker.pyc | Bin clear_pyc.sh | 0 example_startup.pyc | Bin py2json.py | 0 py2json.pyc | Bin restart_language.sh | 0 版本说明.txt | 0 20 files changed, 416 insertions(+), 75 deletions(-) mode change 100644 => 100755 Massage/Massage.pyc create mode 100644 Massage/MassageControl/hardware/__pycache__/remote_cam.cpython-39.pyc create mode 100644 Massage/MassageControl/hardware/capture.py mode change 100644 => 100755 Massage/controller.service mode change 100644 => 100755 Massage/test_manual.py mode change 100644 => 100755 Massage/test_manual.pyc create mode 100644 Massage/tools/__pycache__/log.cpython-38.pyc mode change 100644 => 100755 Restart_Speaker.py mode change 100644 => 100755 Restart_Speaker.pyc mode change 100644 => 100755 clear_pyc.sh mode change 100644 => 100755 example_startup.pyc mode change 100644 => 100755 py2json.py mode change 100644 => 100755 py2json.pyc mode change 100644 => 100755 restart_language.sh mode change 100644 => 100755 版本说明.txt diff --git a/Massage/Massage.pyc b/Massage/Massage.pyc old mode 100644 new mode 100755 diff --git a/Massage/MassageControl/hardware/__pycache__/dobot_api.cpython-38.pyc b/Massage/MassageControl/hardware/__pycache__/dobot_api.cpython-38.pyc index 42d5db17e4f5e0817591e61992841151c8ccdd80..5119330d34092f334a94bd18cda7e55ed6f4dbcf 100644 GIT binary patch delta 63 zcmaF6n&ZQ24(?E1UM>b8uxB&h$i0SBI7mMuKQ~oBt2iwQOvINLHy`J0KhDXx{WvGn OdoISP?b}6|%oqW3I20xT delta 60 zcmeycn&a(i4(?E1UM>b8P`B0D$i0SBz+XQjKQ~oBt2iwQOf;Y3Y(K@xxcw9-(|az) MTibVuFqts|063o$cK`qY diff --git a/Massage/MassageControl/hardware/__pycache__/dobot_nova5.cpython-39.pyc b/Massage/MassageControl/hardware/__pycache__/dobot_nova5.cpython-39.pyc index c53eae54c15287a3e9d439e7919a467335318bac..f69cf28d19d6c783b09f8588c19c0f82c38067a5 100644 GIT binary patch delta 3593 zcmbuCdr(wW9LG5eERSV_0+vEoQXboN0|6Bb31&ku9ukjLbV1h(d&M<&7tXFE^dPM) z$BgVW<&-66uZ>=MD|2e9sm7_M()z1z*)&am$RE`-7l#4MZ5sd4;g@?7QCpZ1%rq+`GRENNv~WJ9)fqVRAWiBqf-MfmF> zopI6?>USiNNL*@b(k}_b#%j{`l4b0ZwD!z0?!{%Q_shKlN=KkK5TYfl#B3)kRhQXf z;6sPfi%11Kkbc5g!iUl_)|F90s@2^YCk)0KwAk1kmMcvaFzbL+Ha>qL+ml(kr5TU< zELaIZ3s4A{fHgoh&^2VV^1(n*3AzWo!I0bMb9aUibIr+;;kj&abwlDKa z_F`j7JcD0B!*EgDsP;aWO(QUT)fe$jxQ{p zvyP4bSH~vRQSbw~O02k;JDZ9JMA@$9)?aLaeF1Y7T{ae*cm&3Iq>*B4;Ez&@z7;7! z#qV)@)|6dv8zjt6X{ahKV{@orjmeU zOm;9^>DE#aR%l7;R6@=`U?4hY8u4nz5N~vQqc`x&(gb20fs@glyFZ=U?kW!V}p+v-w{g7Fc!;hk+Z{ zvceU`^H8*sFHK>!DiXT(s}ohy#o^A?)c$+8UOikz_0o;!*Cq0A z;_LB-yu(Vf*Dv-URzYgyYNF!^{vZ%52yG7mOeFs6>dOrmW#d2Pjp*{aYM0hT%S&za z4=Xe%)QOE2Ns8nrO;;xliLQ=)RBO$Mm8YJookwz}6C94$r|H9>m{mEn{ONxBIF=H# zXV>$#dsusYHfy=zJyXK1-#9Y+pO%IC0(s)n@1MKOy}n`j8T)o8^Cck)Sij)?1}ax z$rHSZpQcH6V@H$me)PYk9_TO-aw~hhvw>&lhtB-PFJq8?JBT}oW@4bIgX#OBlrNUw z4@;c&%U?k6D*&QuNpeu8R34$vp$WbyHcT^mlmR8A=&GJo!_L3S*r(`4>Z3DoGoHn! zoZ^<0L1O}#`U3twIi&dcuO8$j%n(&^oLgGT78>xmhqlWhEm;n_mF)xkV*LVRP6E$j zOuQ!$(pXVfR*ox6ram|S*yiUy;J@(6;bQGwH<2-Rxa(*-wD2v(bu1COo5|~UCm+xs zZ0wiyxnrWRm+=<55?Bjt07T(zhNS>ofPP>rFa%KG7GMXk6Sy0=2iOgWB6%lwJ`vZ%`6SFkz+qq=AU9{?W$p95b4-vDQrqbG+=Z8$=1WBXi% zMOZSu6Zn>6G}S?USL5H3@+y6UP{ERo{pMQ4Pl~0xME^(WIo8x&ow$Vex!B%rE16{B z?nOpy4L!oX=*})hmRzaaQInf0vS&ok(-{nitY55JEbAawRYV%t)}DrVb29k{HCzl( delta 3878 zcmb`Kdr(|g9mn@vb~m`Ygr&MN&8nAovEYaOvcW1Jl}KU?kxj0 zGc`;;d+s^E^ZR}8@Ao_R?w)#qTwWp>N=Amm!v7t&H{Si$>5M}1gVPn)$VHY-4$r2m zg=dQwEhh-EsD%?n0e8R|$eNe@C2C2)VzU%j0=G0;(kxz!TH-HN(*qv0^n?W4vt?@O zqS$p-Ht!U3>49uMS3Xg3!*<7_g;)Zl&m!k6LrJ$R>F$=uNJM*-C^n*N|FFMrC1vbA z=T}Js3%d?_>bRBP*&0?xf@&`}jMHlNM^^>$Y9G3CC2pFNSwb3_H*?8e%}r??`yjK5 z+@Y1bmn69vGiAUozz6IG_5h7Q3*cZ`o=p<%VCA0ryE-vr_`=8vbOFVH6X*u+0D1ry zM`9h##`qwIo)wM6)Yx!vJQg1gg@yy_812PkAJ7ln$&?BYo7wEpu6le@r_dC!Y-#WClK2);`CT>zNag z@o@Y`+SbaM_D+FM%1PDKR8BU#eQTRYLc&Ei!=tq;GTCXW<;R!NDE9$WNBjP!Mrp$+ za=K=?4iQeypo1_&OsWE@_PN=RheXJk&8LWS1ReswkeHOW-n@=4VB06rF)SMModSm@ z6}>`?L|1XA%V~f(4DIYM#Wh8y#3QD0jxb8~=w4P+lDk{vV$HLI^DWzqvm?5|86S-f zk48cvB^)rF743l&EgID;QDYMoopV z)lwxMPs7QV*j#OYY08N;=^!UsYFw5btP5A8p_ED_H=`sYtoYRLcb!O z5`S+{34a|9G`3Wu2)Zp6r{mFtM9XnSj?x_dX&@J)9UMN14=UO38Y?%VNoBiP>0UK{ zfWOB08#U{;BByba*yz=E-L{Q5Phu>}@h}VB-n#t}Tz?H%B~Y&s=+C!T`ECRf*+}Ox zeBrSm4}y*2?!J!EDGvF@8`TsUOW)91cFG?Of2OJVe}^A2!t0-{C-<=R-u#x;!Z}Qb z`B6kV4XligIR-o?vVP2)C4D3nAFE}`(DFeOv{X0em593*f>O8cGPH=pU}#~%=0f*M zG1{5tjU+F5Gl?`~n_<@dc zySw3Gg|T+6Wr2|U*~zy4O>3P`ehBKd>utw~{eJFYdJmg#+riGaZ)mKC!*d+EjVj?W zRkthAD1UO$Z)4#*9DHjw#^2@e+d9OzsX2DN{Uljr$M-!<7By!FLHvyUO?e{z40cII zb0QoqVRu=mJ}t+zI=_p?)0>yQ`7wkB2*;o^qbgu ziCyk0w?BsAJbS3t2WsF68UL0pUKy}?Jao304p9F2rW zmAD$_|BWCFuOYEtE0_U5!{w;8xy*yCJ%Y9`ahx1Se7ekKL4Nvzy=@>5FOuukrx;M{D9~tg}rgeGdqrJ3dDe;z!dOh z-~r%4;2}Wt(zh^r9C!kF3TOhJ1{Q#`z%#%gAikp{FcMAh97ewZUa@f5^i>RB2mSzmf{`(b_pxprjYOw(Tlh#QI>r02 zZfM)A=vHyI(-8y7_S*vDhaFPucW^Bo!y=%O+;?G?N})&`?$e(>dV~%`x!)OA=$IN8 r7e;MF^2HY=H@1t+=3vAw3>A`o_UceumgGuXPu#>x9Q-evtWWz79%(}v diff --git a/Massage/MassageControl/hardware/__pycache__/remote_cam.cpython-39.pyc b/Massage/MassageControl/hardware/__pycache__/remote_cam.cpython-39.pyc new file mode 100644 index 0000000000000000000000000000000000000000..395d656687073da344cf7fb56ff07b3470871a11 GIT binary patch literal 5518 zcmbtYYmgjO74GLu&vR#Y!-hP>ks>BTWwRlnfQkr-8%PjYFpH+>LfTH>p52+uOiyn2 zWOt@|74x7dO$=CyLIO3b5T!&-C`uqG{`I#%`c;`4XPlEfq?S0uBGWm6Vq#Z&}VO-*3k zj0qe!;{qF|aX?}UQ%^}uJ*k)pH_5c4%1bie-ftH;Wv1K&(^>4SY^L3GJF_gwl54cH zEWRv*O1DRrrDs($XO5aUtB4fL=sm31bc)n!=Z ztn{`rQ_#iUI9V;H;oJa-;yrN`V$lY7(RCWM(yoLouV!`Eeyfq3*8jH5Q^bnI)dd-1 zstZZ42ie`AtgXKPZsmqHC_4VXyW=C6sSx9%vm0dZ zonD=jX*wjj{zIE3DTIL8w)0X9Sn(52( zQYy%VDe`=%&!YVz@W@bm8trLn4|45M79*a=o<*OrW$Cbl`NwI#*#WgvXigzMQ_v!V zERC#->)7S0cw4&b%zOD(Dj(+k2J`Zhv-y&QBWUT3pg8%!+-tAW^WnpVb!3;^u9l8^ zW@2{sVAnI4n|wF0swLkq)#fak#5(FWt-4n!IZZROuMv3r7<)<-NmXk#*9pwb90mp4 zuK8s8X4*JX3mU4+p=-GYV>t+rXyOmf#b-lZdr=qScq z$761!*LkTHn4_YDA265m-k8)-Rip(a_#54?xNhCdiI$;RBHgKYzFWw2P2^U3nImD6 zL`~KA=gl;UaIoUU>JH=1yp63_qL|kR>Wv`Mu_BMJ(Pp9l1#t7X14xP?XB9;mQ*){z z)0@-{Spl7sjUG%Zp#Gz%t-FR){WHD54Q5KJPi7@l{~sV)?*(u{6gbMtdZ;%(1go>k zk{rrqmFY(nej$|G8kAcJ6&BkdEvdk9U=7#+)&spA3stCcOi)nmrFamB0mOoMIkBuP z8KQ(bQAz|bfY1n%D6A(NG!dS{$84Tcd4Bc%p#4zmuak!1oFM7bMEEq&;Q`sAKqWN ze4_K>rIib3J3n0Ry!x9@KYHuhkKgZ{du8Rq^DD1hy87CwLkGUr`N^4;_b+#@Thr^|1f@oE@BurM62 zTk-iIsPCDYYEA5UVCT-AQ)FTlJ3zd)im++7pj;>4c%4+aAV+bs3ux-~zoHx^28)SO zLyL(<5fG7%AQ}d+HoxTftzD1WrHae)frn%OweE2@&+Nd?7r9r>cXNX6`K}S?$x`>^ z3+l|wOl#dEiw^b)`_Frh)8O1?d-5}dTx4+fSOe?yBNdAl!NE-RynrxuWFcNHiXE|i z_r80h#F6{%?fC$uR*#Z2?~z8a=<-N!V4)90s&jl-WR$ACUg^i4IP}QA{nqr8-+1y+ zlHYBQE9se?znc3B@ z-J!!BMNN9ON3CvVhudp)eixYVEwn7zUE@Ha+}eYkML(aWmEwwWyP6c91HJ@QQq9U) z@uiiVoRm?LTbqXb$XZ?wsYw4JnmnR#9|u8%a2*YqKL}SKFhx?tNSQKnLBm<}XoX^$ zs6~90rJ4~SA11RFd3CJuE3g|_&dM)7zWU~sn~m-UbL*Tt0V7;Bw}Alj+iHz!y}6^t zY|iawVNZTwe8UDZB;uP#44eA!pqW+z%<_+snYL2<$xOQiP6=LX!;F^~Cfv0Em;@{N z^@`oxflQ8)?kHBO`t#mG6ko7Q!Q*Z-8fDOQ?lt#SDu+uo<}LU_{|ah10u4@n?XhQj zoV#Aa55e50L`gDoavCoVTWM_=I@%liJ9Lo!hmyWQa{68D1b!C>!<5s?2I*O4Nn6rG z<%XIV(j`5N-;S8EQ9>f5g|QwDpB*A03S;Y~(@KamD2x+T1SfcVxvhkNWtDt?sI;{} zFC(d8>Lx^(IcX_{FO76dL+=c*4x9z1$TI>=ktY|#!`MlAzx18T(kSS-pr2bBL!ves zj)|GZ!*OOD)%d&NSU7UK6ppWx!VKnEhaS0JIg9dbVG5CIU3gnKK8F~FG%SsBvd@Pl zHi=~L*t^FrBDy8Qlt|f#N`p!xZl&63M8^q=VC^imhZELFuY^7*)$bdb*n{{y%t5YXGia9j9Z)T2{{DxgAwQP!p z<_P2Vg4JVLa{a>kwZ1?E6`efZyeZHEeje^#XiwQZaj!s4)?GP#=nj& z^2Z5$mB2#;9wx9CAd-(qawC#kk-QkmO*19dZ6QT&u(keZec!*(97FxifRBG4fRq`N z$5gl`bu(g6PQ~@Im*W~#iMI1kNq`*b5TLx7lb+GNQQSHaPP0bBNF?tz z3Pw(}(cD$LRI{vB;+|di@7Rg=9;}QUEq@T8HEB1TdZXq94ess|BAUYOs92iwryAle zRjSUR1}d?mUYq-T-NmVk?xS0tncPyH+`_Ca2Pd~YF}Y>7HF=AFA>dzuHoDBBykkn_ zgCb=4Pa_L7a2G;?=pAh(Ru_^OOj5}6t+buH2~a#UV|0((&G=&|M7jvP!fZJGF5;UA zkl^?sYF9j@bZ`}2>2IcbA^6oGM~dCeztpO|7$pEKF?*y|OEqyqQM^=L;H3aRjSx7C z;yRZW>0=ESOuF0|l#W@f#POTS4(21R40AJ6MX!QOA$~2P%Bb2$UG(sWPFWnf_!VM2 s*j1f}D5wkN?Ow+EF#COJFVZU6P?ET?C6z2u@ 0: # 排除无效深度 + x = (u - cx) * z / fx + y = (v - cy) * z / fy + points.append([x, y, z]) + colors.append(rgb_image_cropped[v, u] / 255.0) # 颜色归一化到[0,1] + + # 将点云和颜色转换为NumPy数组 + points = np.array(points) + colors = np.array(colors) + + # 创建Open3D点云对象 + point_cloud = o3d.geometry.PointCloud() + point_cloud.points = o3d.utility.Vector3dVector(points) + point_cloud.colors = o3d.utility.Vector3dVector(colors) + + # 显示点云 + o3d.visualization.draw_geometries([point_cloud]) + +if __name__ == "__main__": + import time + import os + # 初始化客户端并指定服务器地址 + cam = ToolCamera(host='127.0.0.1') + # cam.stop() + cam.start() + time.sleep(2) + # 获取最新的RGB和深度图像 + rgb_image, depth_image, camera_intrinsics = cam.get_latest_frame() + print(camera_intrinsics) + + max_depth = np.max(depth_image) + print(np.min(depth_image),np.max(depth_image)) + # print(depth_image[200, 320]) + # depth_image = (depth_image / max_depth * 65535).astype(np.uint16) + # print(np.min(depth_image),np.max(depth_image)) + # 对图像进行水平翻转 + # rgb_image = cv2.flip(rgb_image, 1) + # depth_image = cv2.flip(depth_image, 1) + + # 显示图像 + cam.display_images(rgb_image, depth_image) + cv2.imwrite("aucpuncture2point/configs/using_img/color.png",rgb_image) + cv2.imwrite("aucpuncture2point/configs/using_img/depth.png",depth_image) + # 获取当前时间并格式化为文件夹名 (格式: 年-月-日_时-分-秒) + current_time = time.strftime("%Y-%m-%d_%H-%M-%S") + base_dir = "/home/jsfb/jsfb_ws/collected_data/test_images" + # 创建一个根据时间命名的新文件夹 + folder_path = os.path.join(base_dir, current_time) + os.makedirs(folder_path, exist_ok=True) # 如果文件夹不存在则创建 + + cv2.imwrite(os.path.join(folder_path, "color.png"), rgb_image) + cv2.imwrite(os.path.join(folder_path, "depth.png"), depth_image) + + # 显示RGB点云 + # cam.display_rgb_point_cloud(rgb_image, depth_image, camera_intrinsics) diff --git a/Massage/MassageControl/tools/auto_visual_valibration.py b/Massage/MassageControl/tools/auto_visual_valibration.py index e5858b1..d6bb8b9 100644 --- a/Massage/MassageControl/tools/auto_visual_valibration.py +++ b/Massage/MassageControl/tools/auto_visual_valibration.py @@ -10,7 +10,7 @@ from scipy.spatial.transform import Rotation as R sys.path.append(str(Path(__file__).resolve().parent.parent)) sys.path.append('/home/jsfb/jsfb_ws/MassageRobot_Dobot/Massage/MassageControl') from hardware.remote_cam import ToolCamera -from hardware.aubo_C5 import AuboC5 +from hardware.dobot_nova5 import dobot_nova5 np.set_printoptions(precision=8, suppress=True) # 设置寻找亚像素角点的参数,采用的停止准则是最大循环次数30和最大误差容限0.001 @@ -41,16 +41,20 @@ class Calibration: self.size = None self.intrinsics_mtx = None self.disorder = None + time.sleep(2) rgb_image, depth_image, camera_intrinsics = self.cam.get_latest_frame() + self.save_directory = '/home/jsfb/jsfb_ws/global_config/captured_images' + if rgb_image is None : print(f'===============相机连接失败请检查并重试==============') else: - print(f'===============相机连接成功==============') self.size = rgb_image.shape[:2] + print(f'===============相机连接成功============== ',self.size) + self.intrinsics = camera_intrinsics - self.arm = AuboC5() - self.arm.init() + self.arm = dobot_nova5("192.168.5.1") + self.arm.start() self.obj_points = [] print(f'===============机械臂连接成功==============') @@ -62,24 +66,29 @@ class Calibration: def collect_data(self): #移动到初始位置 - pose = [(90) * (np.pi / 180), 4.23 * (np.pi / 180), 124.33 * (np.pi / 180), 61.56 * (np.pi / 180), -89.61 * (np.pi / 180), 0 * (np.pi / 180)] - code = self.arm.move_joint(pose,4,wait=True) + pose = [-45.0009079,55.5785141,-120.68821716,5.11103201,-90.00195312,-90.00085449] + code = self.arm.RunPoint_P_inJoint(pose) if code == -1: print("运动到拍照位置失败") #拍照 self.check_corners() #运动到下一个位置 # 目前只设计了44条轨迹 - for i in range (0,45): + for i in range (0,18): next_pose = self.get_next_pose_ugly(i) - self.arm.move_joint(next_pose, 4,wait=True) + code=self.arm.RunPoint_P_inJoint(next_pose) + time.sleep(0.5) if code == -1: print("运动到拍照位置失败") else: self.check_corners() - + time.sleep(0.5) + def check_corners(self): rgb, depth, intrinsics = self.cam.get_latest_frame() + # img_path = f'photo{i}' + # filename = os.path.join(self.save_directory, f'{img_path}/rgb_image.png') + # rgb=cv2.imread(filename) gray = cv2.cvtColor(rgb, cv2.COLOR_BGR2GRAY) ret, corners = cv2.findChessboardCorners(gray, self.board_size, None) if ret: @@ -115,14 +124,12 @@ class Calibration: self.robot_poses.append(robot_pose) def get_pose_homomat(self): - pose = self.arm.robot_rpc_client.getRobotInterface(self.arm.robot_name).getRobotState().getTcpPose() - x, y, z, rx, ry, rz = pose - r = R.from_euler('xyz', [rx, ry, rz]) - rotation_matrix = r.as_matrix() - translation_vector = np.array([x, y, z]).reshape(3, 1) + arm_position,arm_orientation = self.arm.get_arm_position() + rotation_matrix = R.from_quat(arm_orientation).as_matrix() + translation_vector = arm_position homo_mat = np.eye(4) # 创建 4x4 单位矩阵 homo_mat[:3, :3] = rotation_matrix - homo_mat[:3, 3] = translation_vector.flatten() + homo_mat[:3, 3] = translation_vector return homo_mat def camera_calib(self): @@ -132,6 +139,7 @@ class Calibration: if ret: print("内参矩阵:\n", mtx) # 内参数矩阵 print("畸变系数:\n", dist) # 畸变系数 distortion cofficients = (k_1,k_2,p_1,p_2,k_3) + print("重投影误差:\n",ret) print("++++++++++相机标定完成++++++++++++++") self.intrinsics_mtx = mtx self.disorder = dist @@ -185,52 +193,24 @@ class Calibration: return None def get_next_pose_ugly(self,index): poselist =[ - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0744246875277093, -1.5639895427121187, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.1267845650875392, -1.5116296651522887, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.1791444426473692, -1.4592697875924587, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0744246875277093, -1.5639895427121187, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0220648099678793, -1.5116296651522887, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 0.9697049324080494, -1.4592697875924587, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 0.9173450548482196, -1.4069099100326288, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0744246875277093, -1.5639895427121187, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.1267845650875392, -1.6163494202719486, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.1791444426473692, -1.6687092978317786, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.2315043202071991, -1.7210691753916085, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0744246875277093, -1.5639895427121187, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.109331272567596, -1.4941763726323454, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.1442378576074825, -1.424363202552572, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.1791444426473692, -1.3545500324727988, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.2140510276872558, -1.2847368623930255, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0744246875277093, -1.5639895427121187, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.109331272567596, -1.633802712791892, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.1442378576074825, -1.7036158828716652, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0744246875277093, -1.5639895427121187, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0395181024878226, -1.4941763726323454, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.004611517447936, -1.424363202552572, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 0.9697049324080493, -1.3545500324727988, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 0.9347983473681627, -1.2847368623930255, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0744246875277093, -1.5639895427121187, 0.0], - [1.5707963267948966, 0.06510078109938851, 2.16996785900455, 1.0395181024878226, -1.4941763726323454, 0.0], - [1.5707963267948966, 0.05637413483941686, 2.16996785900455, 1.004611517447936, -1.424363202552572, 0.0], - [1.5707963267948966, 0.047647488579445216, 2.16996785900455, 0.9697049324080493, -1.3545500324727988, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0744246875277093, -1.5639895427121187, 0.0], - [1.562069680534925, 0.07382742735936015, 2.16996785900455, 1.0395181024878226, -1.4941763726323454, 0.0], - [1.5533430342749535, 0.07382742735936015, 2.16996785900455, 1.004611517447936, -1.424363202552572, 0.0], - [1.544616388014982, 0.07382742735936015, 2.16996785900455, 0.9697049324080493, -1.3545500324727988, 0.0], - [1.5358897417550104, 0.07382742735936015, 2.16996785900455, 0.9347983473681627, -1.2847368623930255, 0.0], - [1.5271630954950388, 0.07382742735936015, 2.16996785900455, 0.8998917623282761, -1.2149236923132523, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0744246875277093, -1.5639895427121187, 0.0], - [1.579522973054868, 0.07382742735936015, 2.16996785900455, 1.109331272567596, -1.5988961277520053, 0.0], - [1.5882496193148397, 0.07382742735936015, 2.16996785900455, 1.1442378576074825, -1.633802712791892, 0.0], - [1.5969762655748112, 0.07382742735936015, 2.16996785900455, 1.1791444426473692, -1.6687092978317786, 0.0], - [1.6057029118347828, 0.07382742735936015, 2.16996785900455, 1.2140510276872558, -1.7036158828716652, 0.0], - [1.6144295580947543, 0.07382742735936015, 2.16996785900455, 1.2489576127271425, -1.7385224679115518, 0.0], - [1.5707963267948966, 0.07382742735936015, 2.16996785900455, 1.0744246875277093, -1.5639895427121187, 0.0], - [1.579522973054868, 0.07382742735936015, 2.16996785900455, 1.1267845650875392, -1.581442835232062, 0.0], - [1.5882496193148397, 0.07382742735936015, 2.16996785900455, 1.1791444426473692, -1.5988961277520053, 0.0], - [1.5969762655748112, 0.07382742735936015, 2.16996785900455, 1.2315043202071991, -1.6163494202719486, 0.0], - [1.6057029118347828, 0.07382742735936015, 2.16996785900455, 1.283864197767029, -1.633802712791892, 0.0], - [1.6144295580947543, 0.07382742735936015, 2.16996785900455, 1.336224075326859, -1.6512560053118353, 0.0] + [-4.513801574707031250e+01,5.518265151977539062e+01,-1.237858963012695312e+02,9.085088729858398438e+00,-9.337700653076171875e+01,-9.000016784667968750e+01], + [-4.594435882568359375e+01,3.636156082153320312e+01,-1.064173660278320312e+02,-2.125140428543090820e+00,-9.337675476074218750e+01,-9.000016784667968750e+01], + [-4.595432662963867188e+01,1.059147930145263672e+01,-8.284246063232421875e+01,-1.484527587890625000e+01,-9.337491607666015625e+01,-9.000013732910156250e+01], + [-4.638331604003906250e+01,-6.824899196624755859e+00,-6.758448791503906250e+01,-2.286166954040527344e+01,-9.337348937988281250e+01,-9.000016784667968750e+01], + [-4.636801910400390625e+01,-1.807893753051757812e+01,-6.532709503173828125e+01,-2.261142921447753906e+01,-9.336659240722656250e+01,-9.000010681152343750e+01], + [-4.637482833862304688e+01,-4.540402412414550781e+00,-1.098018112182617188e+02,3.086268234252929688e+01,-9.305430603027343750e+01,-9.000022125244140625e+01], + [-4.640084075927734375e+01,8.068140029907226562e+00,-1.362033843994140625e+02,6.259086990356445312e+01,-9.334789276123046875e+01,-9.000019073486328125e+01], + [-4.640056610107421875e+01,8.061657905578613281e+00,-1.511797027587890625e+02,8.927394104003906250e+01,-9.331819915771484375e+01,-9.000019073486328125e+01], + [-4.638466262817382812e+01,3.287191867828369141e+00,-1.566032409667968750e+02,1.035896453857421875e+02,-9.330465698242187500e+01,-9.000022125244140625e+01], + [-3.178509473800659180e+00,6.977911472320556641e+00,-1.417592010498046875e+02,6.005132293701171875e+01,-1.280102996826171875e+02,-9.000010681152343750e+01], + [-1.424913024902343750e+01,-2.980865538120269775e-01,-1.193396759033203125e+02,3.752756500244140625e+01,-1.278784713745117188e+02,-8.999975585937500000e+01], + [-2.393187522888183594e+01,-2.973175048828125000e-01,-1.121088027954101562e+02,3.928178024291992188e+01,-1.183067703247070312e+02,-8.999983215332031250e+01], + [-3.699544525146484375e+01,-2.981689572334289551e-01,-1.078408889770507812e+02,3.178039932250976562e+01,-1.024006271362304688e+02,-8.999983215332031250e+01], + [-6.734904479980468750e+01,-4.368630886077880859e+00,-1.035898971557617188e+02,2.342595481872558594e+01,-7.085527801513671875e+01,-8.999980926513671875e+01], + [-8.632910919189453125e+01,-1.039798259735107422e+01,-1.038105545043945312e+02,2.330961036682128906e+01,-5.476583099365234375e+01,-8.999980926513671875e+01], + [-8.156823730468750000e+01,5.878097534179687500e+00,-1.439221954345703125e+02,6.846669006347656250e+01,-4.482905197143554688e+01,-8.999922943115234375e+01], + [-8.601764678955078125e+01,3.570293045043945312e+01,-1.308228912353515625e+02,2.318510818481445312e+01,-5.378013610839843750e+01,-8.999922943115234375e+01], + [-7.132132053375244141e+00,3.722338104248046875e+01,-1.065378265380859375e+02,-3.337371826171875000e+00,-1.185582199096679688e+02,-8.999931335449218750e+01] ] return poselist[index] @@ -241,7 +221,7 @@ if __name__ == '__main__': # 标定板的width 对应的角点的个数 6 # 标定板的height 对应的角点的个数 3 calibration_board_size = [6,3] - calibration_board_square_size = 0.027 #unit - meter + calibration_board_square_size = 0.03 #unit - meter systemPath = "/home/jsfb/Documents/" now = datetime.now() @@ -252,7 +232,9 @@ if __name__ == '__main__': calib = Calibration(calibration_board_size,calibration_board_square_size,systemPath) calib.collect_data() + print("=================数据采集完成===================") R, t,intrin = calib.calibrate() + print("旋转矩阵:") print(R) print("平移向量:") diff --git a/Massage/controller.service b/Massage/controller.service old mode 100644 new mode 100755 diff --git a/Massage/test_manual.py b/Massage/test_manual.py old mode 100644 new mode 100755 diff --git a/Massage/test_manual.pyc b/Massage/test_manual.pyc old mode 100644 new mode 100755 diff --git a/Massage/tools/__pycache__/log.cpython-38.pyc b/Massage/tools/__pycache__/log.cpython-38.pyc new file mode 100644 index 0000000000000000000000000000000000000000..92cc5b1eccfc228bac6c091e9277f69fdcba79bf GIT binary patch literal 3223 zcmb_f&2QYs6`$e9F3J7Shh@o@?L=v@fETT$G^l$J+9IwZxdD_lvUcm37lPt&Wv;p8 zW;h#10tK{?4s8LWE!smP``%DnuO#1UuK4(d z^JdOI3X zdZueq?9<~?ujH1LPUEs`sd2VztEb~S>RE9sp~(zpKBAP|B&@{BdxVvDHMbhpnDs#8 ze+#S3X3it}>qWO7)`t_UasalVO|t5-HpObk+BB=9c9&cy?~*oo53t@Q&50wxOlMH37=Ga%tb&zEkV==JaF&KeJ=`FV&D4$-eoO;{s##KKHFg(p{;o3suDs*^> z|GXJ~5XNKeP85ela~W)-BuvsKQv-Wpmie17P1BZToIXl6rM(%7;`?N&a49Va{yNSo zjkjBCx1`TUS7JN_QIuZ*4a?PdzdY~<13i$bR!ksTPR1bmPDGy*%HjO*x!3$X*Q6ZhReB+& zp($<83lsQO&$|N6Oano*?b%b#j!jOi8FX;M8)lu)z}v!~q5MfJ{4nsuRv!Y3+6R6- z099~52sixT!D&1YiSR>=#A`6o2+rwmFDwGwM57D!65Q(BFMyJhA<3zrT}|j+Bi9ZL ztRKe+F|)WTc^NEu1qFV&Yu;?HuC^ZQ1@!XqDw9@}d3_!w;tX0`2~pBX8!);+OHXBL zWbuEYn^{9eYgY*q0;K0+pRE;(}!2bpv|4g>vNlz4$d`J?%im; z5SrR|8?Xw#H3sZth7lNAyd+q%eD_AX^>*u~N-}>HL-nGdRnYH4pC?dE7RSI{I1{yF zqnCxxTy3{+wTmUFw^!eKAvzn;g`B7SJ7d^R?$rO81X$5W7p`wCTxxI3!=Ao0gIYgF5^H3!QxfH&bwHSTk?fR(-F1eQyxaxu z+_B(U+p$F*_S}S+6jNeaoa>mo8voPww3z9h&nc4HBW;J?CGY>!AYxX`b+iW#A5thI z6g|^jx-$h0_KA44y8s+l+XYTjtmU+}ryBRJHG0eq}hp6Uq~a4GLS673B{m~$CGZBCembsUO$ue9jL~uxR9jtQ!K}Yt|fh0PMFWR zza>i|#aUFzkyYeXB+(X7wKR)Ls5lYh;o9xh+pBlH8|&-MO2ILgF#=|cLtHaRdN)ir)p3>>D76X3;nF zDzIirpP?F^hTkNu0*6j&mhR{!x;=GbBO?L8DP;|gYG?kcNXdBg@I2{wUN2>X81<^> zy+82P8O8JXIq=HQqqvCT6%-37ki7UeQ6MoC)%$scRvMORj*NvnGsBieow{XMh67-W zpXx^>JwHmoyCK31PMPXFGQbLU_~l1W|M29i&wlpRXMcJ2#g~V_{Pfu$_n!X!7f*lw zz_)Qe}k3kW^=W$bEd_ml#_5C6vKZIgN YGK{+gd7e?(Mh){_U$JUc>Zsp;0U4+ui~s-t literal 0 HcmV?d00001 diff --git a/Restart_Speaker.py b/Restart_Speaker.py old mode 100644 new mode 100755 diff --git a/Restart_Speaker.pyc b/Restart_Speaker.pyc old mode 100644 new mode 100755 diff --git a/clear_pyc.sh b/clear_pyc.sh old mode 100644 new mode 100755 diff --git a/example_startup.pyc b/example_startup.pyc old mode 100644 new mode 100755 diff --git a/py2json.py b/py2json.py old mode 100644 new mode 100755 diff --git a/py2json.pyc b/py2json.pyc old mode 100644 new mode 100755 diff --git a/restart_language.sh b/restart_language.sh old mode 100644 new mode 100755 diff --git a/版本说明.txt b/版本说明.txt old mode 100644 new mode 100755