From e7b876a3076036954e0d349490072933dbc853fd Mon Sep 17 00:00:00 2001
From: eharlan <eharlan@uni-bremen.de>
Date: Thu, 11 May 2023 12:44:16 +0200
Subject: [PATCH] update

---
 .../__pycache__/conn_odom.cpython-38.pyc      | Bin 0 -> 3801 bytes
 .../__pycache__/connection.cpython-38.pyc     | Bin 0 -> 2121 bytes
 .../__pycache__/robot_ros_odom.cpython-38.pyc | Bin 0 -> 2342 bytes
 robomaster_pi/conn_odom.py                    |  67 +++++++++++---
 robomaster_pi/robot_ros_odom.py               |  82 +++++++-----------
 5 files changed, 85 insertions(+), 64 deletions(-)
 create mode 100644 robomaster_pi/__pycache__/conn_odom.cpython-38.pyc
 create mode 100644 robomaster_pi/__pycache__/connection.cpython-38.pyc
 create mode 100644 robomaster_pi/__pycache__/robot_ros_odom.cpython-38.pyc

diff --git a/robomaster_pi/__pycache__/conn_odom.cpython-38.pyc b/robomaster_pi/__pycache__/conn_odom.cpython-38.pyc
new file mode 100644
index 0000000000000000000000000000000000000000..4fe185aeeeace4ac346957341d9d85f6aa7b8357
GIT binary patch
literal 3801
zcmZ`+TW{RP6`tX3x!j9ZvYa@!lDd~9WiN7Kpg`dot&tXOpOm(7QD7Qiy5dk0S6p&E
zq-yVa7bqYDd1-+Df?@^qB`<yIKPb>2(5HgvTOSJjg}gZ587^1yMN7<_%M6Dz=R0%G
z+28hh0mJX-|N2w~8;t#rgv&n%!UMG8FX$9gJY|BYmGZGAEKa<g+G9sJhUcj(Tr<xT
zEkk|bgF2}{Zj1J6P9Op^))5_0H|>slqBrh~K4-sR%2TapOtoU`)D|16qkPqV#>F7s
zRKc;O{~Qla8P?&Su&{fMU9r88SI%CpVo?8Mm5<|6Pr<u7-_Og?ss<1BFe?snJ^rK|
zjwi9If?uBu%UEYgo<+38<)6J0ieG|>nc#{EOL1X;#tyi$l>N*Xj&hXyjNzzev%)i*
zWH@r5I?(&7t9qdA&zQqRfUWkc&1P%AI@wQ?;waYtZ$2CGh6APVyDM7!2~5dO*^(=M
z#yOj_rB&Lri!*!9q*J;}Z_ds*_*UtkVqCVBGiRgrD3BfH5+}Q5Z`nU%3qI$g4chVN
zv=Sc;7S`MvZ7LtLwp9CbzzO-9k+*AEG3-6q6I=Ppu5!}sUigjfoP0<)B#Qq2u!!YB
zo|hAyWTkL*rjjD$q8;T~Cd=t0KEI3Up(UIH9Y3o4Xqcw^!{|7?Ub)4|B-WKLWs)VO
zlwuI+7(iWoRFie8V7&=hwaSCLQs;%Z32@6KT4Vi@&W9=*7QngMC=cZRg)B80xY{Zk
zzmP@k7_#z?;-QMQ@DKEG9Lq$Besq+iN;a~lD<Rz9kZ*~A_L&URWEP87bTllAq!8WW
zWM5A50wZ}=ZC{q;(J)gfmT!?Z8K2a{U~uAtycrJd$|>UXK=|<lXER>{xB9>rylP7s
zrTChZU$8Gfx^o1dzY~v>^p2S<9~XD_Pq1ktj*SWABzZ|Pco1g0ld10EP`LlBcmo~d
zT|Pkbd4T5guH`|V-TZjv18WD~ZGeg_dTsUdK|Qpeq80x|H|L*v3u|F7oQ1pa7A?3N
zo3|9dg*a03k#&o0vo{e(j+s_hj5){dRby~@mX%k$XCFKIuUCw@H|V;cy>>UwG1vdO
zV$6NhylF0nx2MVd&;LQ)KhY(>fByV=a)c`l7+bU7CE0PDR?c`>9#z&P34MJXvxMJ(
zF5F=h$tN|L)?_BU!>P`pt?6_{XZi--t-H5~+eY^eTG2<xfYJ~7j<v(z;X8cx-m7@6
zyzT{OdjUJbagE)52*8d44V{;Q3<V#)qyR&9gJ$HO*{5}2^3D*K5ujQ`jcu&G*}E&J
zz1>`hd$*t5d-}oRd$*_eo_+{2yZ7|&BJ?Z%q~g<x&nnjhj>@BWJuLMOHc<^$7haOT
zQh2X68_oI-hgNOaUh^e$%9jmx4a@DK738I4up4mjt4y_CX?1O1iPJ5tVch(0U~qJ#
zB}GQz9dd1JWZz=9*qOcHrE|&<ZQ0U2V@nu{jD%S0%Qj{Q9pXE9x-x*=TT4A<ulfF(
z-;lv2zBlK}d8=7rLtdUYz-pVzt+_?H!$9KhX-YQwCUs<kbAmj)R$YIzPKk(h`B=s$
z2vo-W`fZv_ZdQli_F-Hi{^ZedWoP;0$}4j@E)Mk;W*~-BDAivBFB}*!uKdP~`Zg``
zbsFj9I*Bt1*a(sQu_pHwtre!BZIG<^qspdrU-J2HVeSvm>R1JD_xLt|>?2~)gUDsg
zzVWK>HxARd&<kLa5!PV-9Rh&~m^hjRsMyFJIg-+;2e3$L0X(GM5dm0BZ3BJH1IA@%
z<qTcp482jmaRvZp1F-tN4XjcF*vM_j?xpbnvUf>tK*jtutgSr*W(_L=d~Q&Fk2p%1
z;Whnj5FJwY9qKlzBgFJ~sWW)B*Oy6j44WE&E^yQD(_Ffe7d|0;o!3C>@6*5lo#+*D
zrXDuwb#*m0UA&jkd>6W(p%oO$7=L4h<c>7}hsU0M^J*;D`;90oH$O^bbZB!k{|yEP
z<Zn~`gE|h>nj?sT+9d#<qpn&w;4H(rMu+>d@QjYQmeIl33*YF7YtNmzzs(i_XdARM
zca7WyCAnAHOGnY${kb>qZX@B%JKGE?2lw+ngRW<E0i{0Z9HYYw%)@Lm&ow&CfDW_G
zJP*1)YO>be;p(^#LVixCukZB-#1ZWJLv*2QaH{MmFDko8vdYRPl^c&I<uu%=<E1rB
zgf$$Y9SbW;Dyx7TK`zj6#jS$$QDsF1bf87?S|G_a9-<ZWb!G|&Dj+T%Dkbn(0j{fg
ztl9goLi^e<6n3a6%%~!hRUqX!SBOsFyHetXv>vG)lS&zr7d6FtP0>P=lNsNwdaKGQ
ziqlleOU_7zk2X1#;y@S8<W!$KR(Hc6_$?p3rm<H7$J*D(_@zmUic^hUT8R1_K4X(_
zAvq#-QgVa_d0?F+@n6Lm>cb-R@Si10C)3KIy3%}1IK?E%L|4T{sq?AK@IR;Wi=&fL
z<&QI5te@bUl|$-FhoN&&$&q9!xWfF$Lum9&L8s}ukv(Z#%8>7cTlxWXA~0XyHH%S1
z6y0q2M+)u5F2!Lwr|~D@W+!7*jTD9P5(?D1$TYRFrt2p*sVqN?>uhb75SuTEW<{4)
tq<X`g)oe`vh{TJKZ#Z)v|9%bok14bjl)zA$;;H?rrUPs6hoI&2uK+y&jOzdZ

literal 0
HcmV?d00001

diff --git a/robomaster_pi/__pycache__/connection.cpython-38.pyc b/robomaster_pi/__pycache__/connection.cpython-38.pyc
new file mode 100644
index 0000000000000000000000000000000000000000..91b94c78b37487969761e2ff0570898e1485dfe1
GIT binary patch
literal 2121
zcmZWqO>f*p7@iN?>-Fx2lx}H7Y0F22WDW^%fkRa)dVo_7v`A<`vK)_-cw>9FGv1bs
zoKqw9)PKMsIra~5=NBMx^a+Vm{sI?x-q~%lZO5ATYhJ%Qe%_D$aWsk;)}Md;q<;<=
z`-hbE<w3cJZGQ*RO!JZ{;-X{~SDY_xLJ4;!m2})wzT<%kz-8I1LKQk+uk2Tmik$41
zgKDUTP7WZC)aWgr^>;7i-Y-&ZsCU$+4t4*8sY~B69qGXd(}O&GD%HDss7J70*8BmB
zH_mZ)wiENtH`Co|1Hs#w>KuIh(4@89o0{rdGfj1t+9o%!Z@#iWXwqtyYkK+NlfpK!
zG#t?`NG2)zYHfg%ejnTZ1=0et8|;|1+;QFt$3??VdCSiDv4kX?<T)FM&387E0%sGD
zdd@~t*vhsyX2*T-5Ikx<rw_nMA2#yT)8sj7{dO>BZO}$zc8#?oE$=YchR)U>v#VtD
zoDClEgSYeZoedta!Q1%-u#Es`Z)YDLM(bY8&#6Eh80Q4bxgbIa#D3>hX>-uYY-&4c
zi@Fo_tn>3~)-2);CDH<Wf_<n&R&>Hb&!AiE><~KHvrc3dHgIb@{^$iWR}lQ)``ZW8
zD&NklqTF^lO`h28-FZ=Jr&cbH$*g!o%cgamXH7A!w`Pm(%A<LTbk|UmJu|J6d|u`*
zzWo$G!g%POh+jNQODG~fUOvKHg=a?Y>x&SeWj_PSnc|u$@r>=E3bZ&0mCQXYf8*NI
z{t24p8S|J5fNjuSdYqTb+nA|MYLsb4n7&*jqfcFtx!?_Zic-=j7LFooS%P9Zl?@7@
zWfNb^GY>X&A%c55YPcT#DBR8}oxpTXLm=*TzMao<(}hV=)J2md-Kbh5`7Fr}QfmvV
zE@vhOWQm>c+RPL)LekK6y3uTE^CU~layQKm)usKsp}-ek5{u5WdAVmkfcp#H^^+tk
z5j9C1;^sY=&2^A3u<a%Y<3k>Bj|(OMkNEHC{nr8#G+Qq(iuRP1-G2)zA7NZCDhMr~
zunC|#6y|HlVj|aMZzTh?NuUKDslDftv-&0hISH0;IO?q;xpN1t|EedJ&9Lf_zrTrP
z$A9hkqT@$#PxaDze_p1>+{SfOP!@F#<zp!36C#9-8fa5I2F9}-V@H^qbnp=os{A#u
zZb1DC+fo9UxXs7n=+@g1y_Oi{7|E^EDo1joB&ntvH4k~1B<O~6dE)Zm@@nWuy3s0E
zSzeYe^W`pc3#ZG>U4!&FwxxLx@?l`e@>*X|Ptd-PZNCSh*>*;=kxeiawRlb?%qH@f
zH{Pj##yD$$`cr-^p!Zr#G+4aTkWNtKec}#%xubkj>%zud^{K~`W--g-$WXT^{|6fS
zDx#7u(y}<pRc}?$_(RA_OahP2+>MoIXBbtXJ(xFo`lRmstVCtUQibRPH)>RL(Gi_T
zW%x#BXz&&FUHZ&r9Rm*$2$~%c4~5ynNjz2&MO#iPcTqEdz4Mx)%9UTwtJ%WP--(Gq
z;7k|Ya=%6(s$R4ACGKMl0Z#pfdDxgmf-bOIAcjhRnZt|vqOx-X%YCc6$lBdqN~sUK
f@XoR@?$S)RAA;Z$R^yPQ)gy;;$RinE-`w~gwT9(p

literal 0
HcmV?d00001

diff --git a/robomaster_pi/__pycache__/robot_ros_odom.cpython-38.pyc b/robomaster_pi/__pycache__/robot_ros_odom.cpython-38.pyc
new file mode 100644
index 0000000000000000000000000000000000000000..760245cbfb7632722b06e3d96968b1b219c6a731
GIT binary patch
literal 2342
zcmZuyOK%)E5+?gKJx|H@*plDgAXuyttYz$BvDgH09tga?C_$tgLM+f|H91nt{TP#+
zl}BiuWFWsGIRv9)?z!X|1OfKC$G+y|W3E2!R~$)J7E6Nl_*la(7OQH$91eR7<GY{#
zDSzuQ_A4ouM+oIZEb|M9WRe$5EIAh(x>tCmFMPhl0uef!NJQX%(J5mQyS<?3mOasP
z@&&H?i@_-qLm8@JGLjMKis~P%f?ol@3VscI41Qg9KyRqwV(pZ12EH!i#ZB2g<)_@~
zw{X&J*^~X3Ox$_G<UkHzGC5T7i7)QTkz4_OPx5WHvHA*kVOtx#UER@XWhS*Qw{2QZ
zl>`=S)lz|vFZMpxbt<#eSf!78n^OI2)7ts=qn!Q3+1|I`(D?V`qd2R}GOgr$ufv(0
z{P}O0PhUA3BXH6`!7~2=X%Nc0?3gv&ao%{2dzLMD!%q3J56N><;4obCICL0Ek;6Pl
z9fy$=H-6I@v*Rv!4Bl%3r}x20A6S18NU|I@VbdS8CTe<Pw$7TN^xtQ|1`g|v*&1Pi
z!(ahBSUbDWVXy!OYiAb$8zQWotvy_f#)ljHRRFFz$SX%Yk|+WjVH=dG-EaM@Hmz^+
zs`aXA8>(_@=Nlv8r8(9C)-&N{dFvVI8FYh{J%dho)_R!%25wBtpMTHv7>B=pvbkTE
zYEzYYv8n6b+9ro)b9a^((y66;#AKTPAI&DZHc2h(^5JyeUVlDI@!nNlSII=zWuj(<
z((Cw!`6CG9v70^qW-gJ~>+$h&din+|GcvzCC<-*p9T3H+jD+_!n;;XU_c9j#*DPQn
zKt%m^<qKTm%xiKjqhOwo2m&oS(5z#}vJ<3_bQNKdJSRw{#J9mBl-?qe{<2n}cTU+c
zZ}=i6>=>4d?kQXJ8YBm2jkoB_0Jv`lC+s-D?hv~ptd&#N1P80h6&X5yRYpyaT(jfG
zmz|sRz2M;b!Hs0iA@L<-U3Sm*ZrWS2BRkHbM;7+>!JRRa{oCxsKMtFaPI9()lQn2K
z<xE?LhF_d%H=zwKw0jLZ@E7+R_|2Jpu=s-<lJp#X34t7Ki4{tROOZUfmhGp;<mSP&
zHo3(+KY09}rgrz5KM(;0TXc6*qmm-8p1DlcXprnY$C-|yz4`$}cL`rMf*&7myw!$g
zHdVTflO(Tln<ScwL5%Dq*?rSWko&L+4|Q%;8>uQo+i5#mr7|swHj;_}(c4otDeApF
z*amqusd4zU$gQS=5?$KOiW+s{SM{NYY@L*5uZ{L`jM5@B)Ye2i(P^oYT#8Y)k6J)R
zFZDK@6m@Dv*Pi!5(RX5zQbbz*qUH0JAGt)<^iR=x(_F;5wr2*1VrWz)FM4Gg*t}G5
zvQTQe5w(F)#iaFjXA|MSm>-D_NRb=ca;vZ5yzhD2O>hM~1>!_CtgjQf4e|)fyaU4g
z0qSfO71!e<tO)fLgI>k#@q56QbHI<*|EFLcp1%S54&I}pdnau#Ny=KHq9G5G1hrl)
zcieZ|;h9I7DvEQjoNMIK(!VuGn^=b4A?BL&-&HylDi!7@SmtdI>e%$xWjz!XX+Cv#
z=xh-X?h=)6!Ou`<1zHfE8}Cd9i@;3LCu6fev$8&{=wGTrb}Zv{5j1M7dG(Y&NV!Qp
zDnd8Xe}}wr-#wpx7qYmrr_d#>o>Q`zhak&z3aeQ;o$DcN^k2!a=RA4nzD1W29Xt68
z^+}h}ZG;TY(?Uesj%#XYZ7{9174dF5lNv2lbU%Ii<R3d9Ki$~|IJe5=M@kH~cRu@^
zu;jC?Pep8OJ>AW%5&h3U`r_%%SIHK^(KJPI%-as7R6Vn8P)}8*?~;4>h}<Wa0%V$A
uCMd<q-S$#o-b5#UfBEJg(9@Vdfl$XDc#iUcPf~=r?Bm3dabCQ(dh5RdjYyLK

literal 0
HcmV?d00001

diff --git a/robomaster_pi/conn_odom.py b/robomaster_pi/conn_odom.py
index 7fe1a2d..b5616d6 100644
--- a/robomaster_pi/conn_odom.py
+++ b/robomaster_pi/conn_odom.py
@@ -5,39 +5,82 @@ import math
 import numpy as np
 import robomaster
 from robomaster import robot
+import tf2_ros
+import tf2_geometry_msgs
+from geometry_msgs.msg import TransformStamped, Quaternion
 
 class OdometryPublisher(Node):
+    zWinkel = 0.0
     
     def __init__(self):
         super().__init__('odometry_publisher')
         self.publisher_ = self.create_publisher(Odometry, 'odometry', 10)
+        self.tf_broadcaster_ = tf2_ros.StaticTransformBroadcaster(self)
+        self.transform_stamped_ = TransformStamped()
+        self.transform_stamped_.header.frame_id = "odom"
+        self.transform_stamped_.child_frame_id = "base_footprint"
         ep_robot = robot.Robot()
         ep_robot.initialize(conn_type="rndis")
+    
         ep_chassis = ep_robot.chassis
-        ep_chassis.sub_position(freq=10, callback=self.sub_position_handler)
-        self.x = 0
-        self.y = 0
-        self.z = 0
+        ep_chassis.sub_position(freq=50, callback=self.sub_position_handler)
+        ep_chassis.sub_imu(freq=50, callback=self.sub_imu_info_handler)
+        
+
+    def sub_imu_info_handler(self, imu_info):
+        acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z = imu_info
+        if(self.zWinkel + (gyro_z /50)* (180 / math.pi) < 195 and self.zWinkel + (gyro_z /50)* (180 / math.pi) >= -165):
+            self.zWinkel = self.zWinkel + (gyro_z /50)* (180 / math.pi)
+        else:
+            if(self.zWinkel + (gyro_z /50)* (180 / math.pi) > 195):
+                self.zWinkel = self.zWinkel + (gyro_z /50)* (180 / math.pi) - 360
+            if(self.zWinkel + (gyro_z /50)* (180 / math.pi) <= -165):
+                self.zWinkel = self.zWinkel + (gyro_z /50)* (180 / math.pi) + 360
+        
+
+            
+        
+
+        
 
     def sub_position_handler(self, position_info):
         self.x, self.y, self.z = position_info
-        print("chassis position: x:{0}, y:{1}, z:{2}".format(self.x, self.y, self.z))
+        print("chassis position: x:{0}, y:{1}, z:{2}".format(self.x, self.y, self.zWinkel))
         self.publish_odometry()
+        self.publish_transform()
+ 
 
     def publish_odometry(self):
-        print("ja")
-        q = self.quaternion_from_euler(0, 0, -self.z* math.pi/180)
+        
+        q = self.quaternion_from_euler(0, 0, -self.zWinkel / (180 / math.pi))
         msg = Odometry()
         msg.header.stamp = self.get_clock().now().to_msg()
-        msg.pose.pose.position.x = self.x
+        msg.pose.pose.position.x = -self.x
         msg.pose.pose.position.y = self.y
-        msg.pose.pose.position.z = 0
-        msg.pose.pose.orientation.x = 0
-        msg.pose.pose.orientation.y = 0
+        msg.pose.pose.position.z = 0.0
+        msg.pose.pose.orientation.x = 0.0
+        msg.pose.pose.orientation.y = 0.0
         msg.pose.pose.orientation.z = q[2]
-        msg.pose.pose.orientation.w = 0
+        msg.pose.pose.orientation.w = 0.0
+        
         self.publisher_.publish(msg)
 
+    def publish_transform(self):
+        self.transform_stamped_.header.stamp = self.get_clock().now().to_msg()
+        self.transform_stamped_.transform.translation.x = -self.x
+        self.transform_stamped_.transform.translation.y = self.y
+        self.transform_stamped_.transform.translation.z = 0.0
+        q = self.quaternion_from_euler(0.0, 0.0, -self.zWinkel / (180 / math.pi))
+        
+        self.transform_stamped_.transform.rotation.x = q[0]
+        self.transform_stamped_.transform.rotation.y = q[1]
+        self.transform_stamped_.transform.rotation.z = q[2]
+        self.transform_stamped_.transform.rotation.w = q[3]
+
+        
+        self.tf_broadcaster_.sendTransform(self.transform_stamped_)
+        
+
     def quaternion_from_euler(self, ai, aj, ak):
         ai /= 2.0
         aj /= 2.0
diff --git a/robomaster_pi/robot_ros_odom.py b/robomaster_pi/robot_ros_odom.py
index c68e323..ffc35d6 100644
--- a/robomaster_pi/robot_ros_odom.py
+++ b/robomaster_pi/robot_ros_odom.py
@@ -1,19 +1,25 @@
-import robomaster
-from robomaster import robot
 import math
 import time
+from geometry_msgs.msg import TransformStamped
+
 import numpy as np
 import rclpy
 from rclpy.node import Node
 from tf2_ros import TransformBroadcaster
-from geometry_msgs.msg import TransformStamped
-from geometry_msgs.msg import Twist
-from tf2_ros import TransformBroadcaster
 
 
 from rclpy.node import Node
-x, y, z = 0, 0, 0
 
+ser = serial.Serial()
+ser.port = '/dev/ttyS0'
+ser.baudrate = 115200
+ser.bytesize = serial.EIGHTBITS
+ser.stopbits = serial.STOPBITS_ONE
+ser.parity = serial.PARITY_NONE
+ser.timeout = 0.2
+ser.open()
+ser.write(("command;").encode('utf-8'))
+leer = ser.readall()
 
 def quaternion_from_euler(ai, aj, ak):
     ai /= 2.0
@@ -39,62 +45,34 @@ def quaternion_from_euler(ai, aj, ak):
     return q
 
 class Robomaster_odom(Node):
+    def __init__(self):
 
-    def sub_position_handler(position_info):
-        print("handler")
-        tf_broadcaster = TransformBroadcaster()
-        t = TransformStamped()
-        t.header.stampep_chassis = time.get_clock().now().to_msg()
-        t.header.frame_id = 'odom'
-        t.child_frame_id = "base_footprint"
-        t.transform.translation.x = position_info.x
-        t.transform.translation.y = -position_info.y
-        t.transform.translation.z = 0.0
-        q = quaternion_from_euler(0, 0, -position_info.z* math.pi/180)
-        t.transform.rotation.x = q[0]
-        t.transform.rotation.y = q[1]
-        t.transform.rotation.z = q[2]
-        t.transform.rotation.w = q[3]
-        tf_broadcaster.sendTransform(t)
-        print("ok")
-
-    def __init__(self, ep_chassis):
-        super().__init__("robomaster_odom")
-        
-        def sub_position_handler(position_info):
-            print("handler")
-            tf_broadcaster = TransformBroadcaster()
+        while True:
+            super().__init__("robomaster_odom")
+            self.tf_broadcaster = TransformBroadcaster(self)
+            ser.write(("chassis position ?;").encode('utf-8'))
+            buf = ser.readall()
+            xyz = buf.decode('utf-8')
+            self.get_logger().info(xyz)
+            xyzlist = xyz.split(" ")
             t = TransformStamped()
-            t.header.stampep_chassis = time.get_clock().now().to_msg()
+            t.header.stamp = self.get_clock().now().to_msg()
             t.header.frame_id = 'odom'
-            t.child_frame_id = "base_footprint"
-            t.transform.translation.x = position_info.x
-            t.transform.translation.y = -position_info.y
+            t.child_frame_id = "base_link"
+            t.transform.translation.x = float(xyzlist[0])
+            t.transform.translation.y = float(xyzlist[1])
             t.transform.translation.z = 0.0
-            q = quaternion_from_euler(0, 0, -position_info.z* math.pi/180)
+            q = quaternion_from_euler(0, 0, float(xyzlist[2])* math.pi/180)
             t.transform.rotation.x = q[0]
             t.transform.rotation.y = q[1]
             t.transform.rotation.z = q[2]
             t.transform.rotation.w = q[3]
-            tf_broadcaster.sendTransform(t)
-            print("ok")
-        
-        ep_chassis.sub_position(freq=10, callback=sub_position_handler)
-        print("sub")
-    
-    
-
+            self.tf_broadcaster.sendTransform(t)
+            time.sleep(0.1)
 
 def main():
-    print("jo")
-    ep_robot = robot.Robot()
-    ep_robot.initialize(conn_type="rndis")
-
-    ep_chassis = ep_robot.chassis
-
     rclpy.init()
-    node = Robomaster_odom(ep_chassis)
+    node = Robomaster_odom()
+    
     rclpy.spin(node)
     rclpy.shutdown()
-
-    ep_robot.close()
\ No newline at end of file
-- 
GitLab