4Ss3aHu7{a
z#^B59h3%~w{DkqPH}93g1YR$3Y3<;A3o6$muR)|*FyLlg@b9{yo(G^EUK!Zw&2
zZqKRHk(M0657pe^{FnI#`&nr0j^2ar4$23bM+K|hs5woU8E|i3
ze%l`q*(A~|6GhG+-KP?O2S)t!GgQp
zToi`*3$~TGkf|~Bx#3EmgJAZCWA{CH9ifD&sI>|=0XhdQ)uD+y8bJUrm)`rTvQ;M94yUQM5
zD47Xg$*nW3V5mrH7Tp(FD9p`bQ{?d1*frmj-RjMtE`D$3P`nPE+0p*v6lIKHfNG}7
zy;~mM2jYr5$vulFQ@A56|3&{_EQfTQhWthTU#NnN9e!{EGGtIiyW6^9TnKo#A1Hui
zx{PurL4+&Hx>r;U#8uHwsH+|ZXg7@gZwGahGX{GDaPCJR;ILElM=uuT;0}<6{B~7V
z#(M+I0Fp9rS%9Q86b^uZK`;Oq43Y&{96D(dP*{xZ1)KvG4FDZlF1XvGN$^7!f;eoF
z7f5bPlKBdm5U8MBG|(6aN5bJShb998+W9H~@#A@NL*rM2yhRdfKto8*hpF}_HzCs$
za+>~Kk00ZC*boj$ilLhanyl5KRT<@uKIAh0RU0x>QE^1M{Zc?1^|K8I|Jcmm6$gO-
zWNd0U5>~_D8~{LL4DJHX9rMd@IJGgxj^OA{5>gs0BZZJ5$wvPui46Hz;oybZd
zAW#U&>Cc(qAP8v?kPLzxED!)HgOCD2WTc_w-9kZNDFh4#C1nzMHmH;=^l<9KJR+qu
z-Ux>wqe%dmTxj(FLdd}6vHl)v-G3l5FnL)&O3~%tT#U@fAkv2+_%~ohN~Yfs)F?sk
zdK-u%l(-}Qve%@yMWkv(pp%xm>qZ0L{M`Na57u;6
z*>({Wz#DC;X~3ul@)wRkG;YD;DwS_fd$FjH~j
zbJJz+3VX%{SjfwYZ+_V^NmC=|6l==6t5u(Jpg3H%Gy*PX{E>1Ft-~SE25aORdMiYJXkBak?9m>f5*D#Q)f&s<{
z4S@Wp0LB0_FaQF8{HQSccs!|8{AQ;>O`JU*04AsGVUGL`psls_=0R3OU{v4{RS+2R
z90CGCmZ|8}z2doORZ?Y*XK6etfK=8-QM2|%+k8+0
kS0QO=C}#8MGXA-9cLK_d;O$1*6ih}2N-r#|rmIf>AHWbMUH||9
literal 0
HcmV?d00001
diff --git a/frames_2025-11-27_16.25.48.gv b/frames_2025-11-27_16.25.48.gv
new file mode 100644
index 00000000..545c92c6
--- /dev/null
+++ b/frames_2025-11-27_16.25.48.gv
@@ -0,0 +1 @@
+digraph G { "No tf data received" }
\ No newline at end of file
diff --git a/frames_2025-11-27_16.25.48.pdf b/frames_2025-11-27_16.25.48.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..bfdd0964c7f71fbd20609ea280a196b8713b5b18
GIT binary patch
literal 6022
zcmcJTc|6qX+s7r@vrk!)v1Xse%otg-MM$>n%g|snW-JpzWXqnd5ZU)7L`5Qd_9)qo
zG$mP6gzWrgw48HZ=lq`M`RAFL*Y`X3bzk3m`CQjr^Sa-{m((?-Akwn*!jG3KcIaV1
zFc5F=La(3z1nHu2P6THloMbYj2Lgd0O$?TR_8{G{C<0m??SQ|6rdLv;_au0rQLgkp
z_x1F3bdEw;o)1)}I(TTEO}esLM{g)9TI?sGc;}I&xa4c`?TrlUn&{BbuN|^nnu!i(
zr)MIrh4KuRH{#qqg&O=RKgK!BKmA&z3^Z?L2Y+C%R~ZqGvwq<&3>jzRd`dtd!^H%m
z)zGQ{&nmH(rJyHnI%*Dv#ypJUhNj8>*##Pxtb4;G9S*)NALs*!e?T`Fl-8PC*b*3W
zq#9qhCwp`U3rv_reGJ~CO>c=$Xc=R!G95^(*&h51aAALwf{-pj1x6P~YeVMXpR!nc09*w*5bJwJAWWC5Dk?$m#pfYfBKe;9I
zTg^lLG<*o>jR+*|fC>s^1L*}qfk_P@NbMXD0t7jrNLP}gq>dj~kR~2S_=~rr6j%xj
zl>HSEk`w9kb28-b$$%i^>uzWuNZ;PYh~RoS_0L$!{dy8~5ePZ#(8PFn5`eIu-~Z?M
z${2y)N6kciqNJck94*aFxE(JTK`fOu$M79|3xSRRKKdN^lV-vh+;~RYKw!j71;u3%cg@IPo!04i|H;F
z)zV_L+hh@LtEvyF7=p^{vYcweZd#!4nYZSaeR;(nRmbn-nDWV)5#(np3(lOB@%tWk
zug34mmy(Tzk;->>sf6n0Qx
zO|MOs!c8p$i8OZmiJGpKkLw?9znJ$vZX6KuqOZ*SsbuPg{_2Gzl8Yr3b+^RrCkszc
zmGDAcM#}N2RaD9X`=jk~wvApL(3{QX6lGew?eJdig?1KZ7UeJ>?@0%V#nbpVlS2Fa
z6#HP>OAovvhj&?W?g9-U(M~Gfx8|=G0E25Q1Kmz_?S<@xC_U?U=v^CA7#4^rZ_7^@
z7?$qdUT;z=>^(x=@=BuKbW6BOEyEDldsh2QH^ifFue!a@*XrtYuPgQefRW1(dkfnW
zZ!alur3(_=$xq}wwY6faEzp_%FoRZJ$F3(kFTyABr
zG)w7}Q8RqKxmzL!dWoZ|;NYukT5{XUvrEw5a-2Zl^SgH1w)SR-2n}dBsD2
zTsF$~#*T;71FCsNUyX7=Z!^_Oe9>4=Tlr#ytBk3zU2aWZJZDn6${5ahn>mKDN9}o&
z`?HaHs>}E0LDJk=cQXq;&rVGZWjiZS?Y<}6yi{{_46wt)IQHS{UAW
z&dpip*yA)@V;>I
zM)IA4jd}|!-io8r4h4!CCnW4vk&1}(R?W5w{C4PhjJZbEDFvSx#p35@_n(^=v?6Z!
z%?3Fwt4H)3#NEP~D9L`^(UH%Z+-E<&dWxcaR1V0sa92`{$v#%kSL=kl)q3^Q?i?Z>
zZf17GOxF;>G2!qn17S-a#J9}8pme=UlinwMS1sV$9G`x#+P<0L2d(qs<99jSU83@1
zz9-({5D?Do0+nV*(QOn$p)ehgP*pugVGA=-k@Xo()QgieyY4GyO)+;tW{*=p6{pbP
z8(EpcaVr!emBzTi;5yW(*xx?5K2I*qK>0O1F^+NHW>@jJ^8xGZsH#Zn@*)CYBCX
z=!;6B4!i#cp6E9{*|f8k6c_0CrD6alm<4Y&^D$fzxvnc6-(TMS*ocVQcvOVfU+QwH
zF};^w9vmG~1nf`D;ygMol9_rUC0&p>mzVK*gP8?u;n&Z3bYZX`G@X-vC7sPuTe2jP
zf3~9Em2)Cp0uj4}Zd3(*kG#>KKRWw4dNKN|-rTiy5exC|D;nPG4=279-!Hh=#y)Iv
z0hHFG6}VH9K=YD>3Er-fob7MfFyetFy(9vAn$d
zBA?4>|I@GP8@8u2ChO$tc0DdK9eW}l;GM8`@#e|9u*Q~`T?#byPgyE|q-8<(TtATlvJyu>l?j8;I-|HEx
zprW#~1;iWrO4`L%E(9m3GgvsudNS1aC~uZXOchDz7H1i*MIwtU2?%`!b?EY)Z9^8
zo=Tg5#U<~6>yj?)$MN(Z^g;!MS--#V&PLa6X;_Bm94|{OKQ^Q8CbZy@M2k7t*{f}v
zi@5d1`-*Gzli578D-mB3=C(CZQDWl*1cUHm^N)r^`1!+^b7G4J{T5xnZ
zj?vktA!MI5Sd&$BU!GM|+I}3FTZ~>x*qkEFbv<43j`ee_uXXb+8I|9&eb=yVlFHb-
z$k5wE-&jyUydA5~ZI{BD1~vV>bNUs-tL$y>8kA95jGE0OoQLPsMTm7&+jy!
zj})`?(E0S59up!ozwWD+nA)B}T?AqG=&;JX+6AAnI1{X&c}zx1=7I7}`bF{Lhd375
z<=A@a8zDI@V|Lnw@r$SgwPBV$2%;Q;sJ}D(lEAm-S{p^^+wqW|y4PnISmwK&Eto^)nicn#QaAquVy2r<2w8sA5x3
zK3d-w?q|<_GEfo-Uzw~@c&!vOEBJ_cfPv>+bC|IOC)cavib!*g6@S=y%|@Dy<_R}5
ziPhCXjlB~s=v>3J8%+0aGLH|rMOX(rjxjC5hE(ZgUhmZAyh3{fwl%J?gz5<$JbCVBd(d8w?&iG}hSJG<=0qT%
zj%nlxqcTsu(7j>Sr+e@@4jynhUfCNJChw2a9A7ebGQMkIef<~!e!H|JK-2sj0YuNd
z!C|FXgU9sU2@Hp9M-ctb?xrWoAK;bh;M)5t2V&0h7wa1R<|Q5&7*Sxwi2h*1Gl9#t
zUXL~M0eO0-I0BCjw<74p*zKy_*k_g@m!vX-T^eXT+u4oZsW0&wzbo(9*Loc+(70o!
z24mQ|GrttR=EctZYUe7$O`HHa%GfaM`@3kZT3YI^5JlEI(9gpH5zh7pnhj%ukHoVw
z4OSlU>aU}hjm{|)MBL!otUa+i+>PBY17`NUcz40SmP3VOO36$3gswJ%lT-xLK}O4`y9tJ8nc=vVHK7x|JC
z;8$LEp4EG(d6Mbvq_~&)LmgJzzIN+@%}r^5_m`^GjC*x?L#^Ip?&q0}I6}s@f)l(g
zs%pZ6pqBnE5umjw-mB@?JKeDdIgzy!Ro1MvMwlHT?1b0-+LF4ZtqaeWkhrUWEMi)B
zR%QDvz+K|QA8C=6nKdg?C3OW(k4(7$Sv4OV*&5{{1~!-Hk^ZF&fzGWXcJZ~PW7QTj
zQqum_<2_kx4mE(RF^;yZs*i=7*o9V29t5ZRM`~FjGKS~0{tVCCO&@4Q(YZw<_l&5x
z5;I$;59{J1=2aJ2M-defuU6+MUcq#4%Z1CdHi}>77RSS6^%16zg7D5QLGh9D
z(rI|-!$K1)lZ$m{mON$PC
z6~kOwm(M6+yc-n7e5&(nnc3-f4W`{pzLU}s9~jcz&oREtD!enL!2XhM>N89+Yci~6
z7s-xR8oIsFF~!)@0?7V0u{ca-6sDn~z
zJ)prUDugI=vPc*4O^oS&ZbVWnvP39ZzqCCu5@Ev@&F+e93GNVA3_I1J)v#tApG-G{Ogzpgpj$z{|z!&8}#DZ
zfGiEG06$&kgojCWQK6D1^Bv(z#K~RL@jP
zyLrv$Ktg%vPS4`WWUfe?f6@OJ%OM@7p?{J87pfp*haa4P3>nnXo(>)uHv-<{2MQpW
zE}~pX5aE)l{v~xI33ap!>hd)sv-mizg<;T
z@jgIHpp+~^4k#r9Lja)=FdPVhfaQSJhfdlA6c*!f4(EhL1Hp%ubDj=p68w;ZA`hG7
z1(MrRWWGWs1ZpTZEi}f-nQ%DFp~;AVcD)Ql{&=3;(E8ONZ;^x=&`^@|VXFPfO~^Eb
zoTh)*QFBIl{8B&{^|K9u{MgLj6$e88
zWNaEZ5>~_DoPZ!x4DKAx6Z6Y(IJGI}3c=ZvB%};PRvIZwl8+qZ|F1Vvmb|Y2{SB8x
zNJHcxFffAT3`c;a!Ehv;v@!$?EDe!C$U@|Ra5)lVltYk5l#wM_A+iu88CZcyJCTz{
zLSayn)1NaTz);d4U|A$NSYRMb7AXye%F4jVyM=)v(nvTQM#?1eY%pm#*x}TNc|=NS
zya^6NMw37YxzHH?g^)qWWBonU`u{*=5c0Bql%k8jxfq#|L1hj@@NdA1luW-Ns7Zps
z)eta87;z6Ui`M0GPIS2|aHCk2%i$81_~NuG<7H0GMC3?dlls-puAx1o?CdG&V{~&T
zxac^YHIJq_Bo&=A7kK(sGjh6J9z#jdZAs+zzZsO>G8-cfKYju>_H{Nk>GG0LzNV;8
zCBRuXIu+PpA)jWQ*!O72zu|jp`vq@1e^hh}k_dR{H?jSIIya=`NH6l4gH
z!8_~^&f8$C1vIrTXjd40GJd@KB@BC;hS}P2fCuv?KMXdepfG?l7!$5{H{CR?oJtNX
z`SR|i^?RF_kpV|Q*Ku$Er8xbfmE__ii~RlH@CzaS`C~LQME|HbKiQ$I+3ev_o;(-uy${yy(?*Ka3*=-(VMFvF&9Z?5E
zpf8|cFm(ASou+p@Cr!L?AJtSQC7Z62it6<7h`Y2xRJkhZtnn-j#{`sAbx~BTeKGc*
mR3HzPsHrKY^XM}ExpPkf%7ftJLE02tRu)DtEUclgN&g?Vx+D$&
literal 0
HcmV?d00001
diff --git a/frames_2025-11-27_16.27.10.gv b/frames_2025-11-27_16.27.10.gv
new file mode 100644
index 00000000..545c92c6
--- /dev/null
+++ b/frames_2025-11-27_16.27.10.gv
@@ -0,0 +1 @@
+digraph G { "No tf data received" }
\ No newline at end of file
diff --git a/frames_2025-11-27_16.27.10.pdf b/frames_2025-11-27_16.27.10.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..83314931a71914c6661dc6910dee0c9c140f8c79
GIT binary patch
literal 6021
zcmcJTc|6qX+s7p-OLj#igDBhVGsZ4kWXl$^4h=?Q#xjA=&~EB$Ey;0000fV{t@`6X}ja6ETVyE5c0-t&9wJqQocd?(2Sg(1lO6O(hGzJlNtb!!esyi0J1`pt|UcC9Y3xhWdfe~7jJ7(uqYTH
z_A4SJC(`HVWT@Yh0YG}U9WVfpmZhC8(f)AipRpAG^(06W06FYX#yU9@0q~#S|L6F^
zbip6Pro%o{Qc$CgnEq1)^5{QBfFOS@3j+Dex_&ML0{y*?f6FPdESS#>~3KU7kk>0Bdj^9JU=(d+D@uf05BRXjGb#9LtCkP9!bcvS6++3+nOnS)WD9Kr*S8QS_
zGec>URxxn9zD+m_dX23t_w?=L?~Zw+efLE_(x*$lxl#7H*g|FqrQ=$Xs4zQf*L#-s
zq*$1__l}e3W2!l652a%Ej(Vz(a@3}{Ei9Z-l?iCeF#x9y#jl;==l^h`Jhzc&K1=oD7dJhAmGa2X
zXWfzhNe=3qYm94k<}3~JpJj{|`>%&|oisjWP;-ZEd&ruW)i32$2?}-R9SVn4isGO2CSucOlmNia5
z7#bciRM$bWjaq$6Lz>h2aWAvZ%iL~NrgabARq%0{<<{y@*f-Sqq;f@Q+)SO59+(*A-SFb;~B*|>@QpCzt
z^|^qjG+b3b5y^ub7qmil1ZPhvTH#Zs86LK>b!ixeZdh%jf{8f90XIr
zQk`K*)IksaAdGuXjn(a}#Yg*kel6+7^JO4j8@lVP2;5c&i|8J<}aWZ#>N>Xf3wd
zRT$h)E%px&$Om-AWpErF5lBxym6XaiKAV&FWrL9kcf+%bEjl=rg`V|J$P-yTh1o<$elOOjOaC+N6X
zU7`?|y`EwJwsPC#TjUY@M*4Q|l&C2}e%shoKT@YRUp?WnbvYnMq}{}|-O;J$!AA`}
zIdoWNCa+LUXF-$T%2oe(MY_-_oYoVz8)e+F8c%EB0-t=dS&vR+5}*-FK@9xoG#F3D(xB10@tXFoP-2`W?Hzw|HBB?c5O}L
zgPtQGte>C}!9hTtC8sAr{gsM##lfB}@l1k#d4YAUp<7s7U!4ExkCZO~CJtsQ6K8PI
ztCBl=uB~yrA^aztv0m8DlHG-ir3D!kRpa~VG<(%=MMWiV9$8D0wZraXle33T
zoGmr;Sy*)Qxh-PHdXhlTPCJ*OUXDm>ts<}@v&(|hYRyg@h7kcJA0Ll
zvmtlix!trce?F6Acr)Z{?CiD@I!tin;M`!g?L?ArcL}|CrR?5B`k3k2QPz>#;Akc`
z4$NeY%(|QXV}rWQiH?gYe4YVbijO7?E~QJNpR+{Y9Ts@wL#uXOE{%WufyPSfbU5G8
zax}fIdriPTv%fO)rF}`}OF+vJRQ4mxV(jJwakllvqFbb=b#QT
zKcntg1gE2{p(u6jLsm`>OLh5(_XjdT9P(<8vguLHvjwfCZ+7^Ne5F$mQJN~X+LAmr
za}QC1#!hOV`)IKN7v|PI6ylPb(x~$xtWM1)>9<-D(>E^qYo#B9iNYSs-l1I(dh`U(
zB(@w`P3;|!)i7+KnisQxj#U_7+JhjAk;w8}!A9phBQ6tuObb?m-fagY2dVVe%aqn>e#Oqz7uFDu^5Y+TqloBp&{d(n(?498rQ{e60L
z(bW$0Vs!rvD<3C!g*Q&tGw9I{GEG3DWA>C{-+@=?UbKg5<`}h$1;zPK8sk`2UUO;8
z;&bc$`0O3ud&$g$y>{#Mo{Fan;EZ-z=hFl5LcR>Cyz3X0YL)d?d4{&l0?#KZ>`_G~
zpMJW&&)>zG`MkTp7qK!{CetBV@k?v9L(HR
zTA3?G&~Z6!D6LiQyPhWq2%a=0qn_nS#H@1Hs>$w!&e-YMPW6k3MoYV~z$4GKk|_0i
zBEqqExAZExrYkxw1Vt6(NC30z0pp^sFVP5}>oKx!=paciyz0)vK=z+C9#_tCwV}SsY0mk%N+>XN@`Zsdd>+y*4CxK366V#buRiY
zo4YDyXTM2WE!E3IpjJ-Rz=|0JW#F~=6foX
zk*>Y+luK(Jv#fhrDmTQNbF=c)?m!!EzX*`t+4AA4S0$%b@^Tf;xXkoN!p=(aQP15?
zI`-(oO=ouBya{IZaoX-F!bvN4fqlJZvDB4PeXqu_Qf}nx5SROKgzU@tFAD+_1BLvydM*CHF~1PY~I;q+P%36WOw^owwiXoDyRRo+pyymMqRdm;Vu7I
zw;N>@!G2IoeQ{8*9VmaRf}6!UoE2Wx7ahr
zQ`$00n`YP@g+Kj~5^9`Yu_9Vfm230VfRjC=;*&K?t$0ZH=JFiMtB}su_Vu7eOl9G4
z`Hg8&pjY`wd&Zho1$)LYTVqDqWF7}@{9g-Q-JvD{MH
z&|q=l6ynX3Jbe@Wv^E3%2_dE8w@vrnVLyYZ1FBw!cIcbrSq}8co8?aQ$$J?#UuEY`
z3HR-dU@WY9NH46n>lem&?#)t>;rS*dhTU}T)4-5Vbg7P)>ECALB}_=MzNMM?0+-Gh
z3#!;fv0`NUqc)l+=o?yXs>*QHX-Pq(65E+S`h=Jgn$(WcfGlGL^ynYiE*Jtoj0Wj8
zQ_8IS)YyatjKfant0TV&GCar*iH}4TTu9U^Y>Ep-nz4kl+M^o$n}wu<&ef{_
zAsW%=-6%KovOOarU$XX$2}kjut#GJ3eRYIoA#dJ8D<^sZj74_G8`h3qrHX2=;He
z;qABmZh_5l>g90(iDUamd69mh|2z#I9`b%32Vrm&LmZj$$k7*;b_&O;P;u$_fqol
z-7Z+wt}~}W?9_A0H~m)`0wG)q`3D2Dg5pkyd1GpUD3$APX_9RX(Zx7nt$#ZxqwTS{+ki_y`T&QWfAl)PRAKoDWm&Pi{h{
zDdaT$yBG{;M`*rlMercKW4&I{IfD0{O9-zbg)a
z{K?pq@Fc8;#oGWt23Y)MyfgNf;c#jL>`kJrGf7AoL=1=$Bgsb&^8eQxB}QJ?|NcgZ
zBY_Zc2po(gIU|r@AQ*u{kXD9-gMknjQVb#vK!}qVqd1a0B20{Ag@{2=WMBm*?L-`i
zg2JIBr$1*xf}x~Az+xzJu)qMg7zzl6ioxLI-NL~TAPRwilQM}s8yqMOKb-n7k4Py^
z(8puRXc7P+7aEmP^=LSEL7Ql$Bti;)=_6m}Sbe*;#eWcm$3^<%s2
z8o^9~OCDh_5+vAgs#~yzsTeAG!JwF_>mE$y4phz1IFpphrS?$WupYFmH3Ft`2lk}?
z0gMK6T3rNU`qofC3uP`DFp+tNmE+Dt*WeNEn2)FlXF21cN@oAZLyavBFRO=I`1;#D
zj>m>WXIg;}SF}FcQTv*C;Pv45Th`DQ(vy*4gU=+{PnM5ebrL@<4{Y`a`hNNhn~Cq8
z0-Z{4m009X5EHy|6?w-^*Z7&EEL&24EPrrjqSY)iPRinY&r|
zT04cLnl+cE(vVkTlTY~v-g+6^N9}0%Cy1})(3EWaL8Z=}e(}b;l~d9^pxvTMeQoa-
z(;uRIKAJ@-*748d`~Rgj{eqR`+9W3S`>){_LHzT#XsCnvQE+~uLoxCH8U=Du(8YRS
z0MH)=zyM$j0YCxJ9|cB-Kp<6$-{=&iink^JAmofaOp)L5v$C+*Jje+33->#s2!=pg
zpkOd``6!LDTMWnX82(PGiF8U9bs0JNsgoi1PF$eMmQ!SoVX8UCDHq)$
literal 0
HcmV?d00001
diff --git a/frames_2025-12-02_19.18.18.gv b/frames_2025-12-02_19.18.18.gv
new file mode 100644
index 00000000..545c92c6
--- /dev/null
+++ b/frames_2025-12-02_19.18.18.gv
@@ -0,0 +1 @@
+digraph G { "No tf data received" }
\ No newline at end of file
diff --git a/frames_2025-12-02_19.18.18.pdf b/frames_2025-12-02_19.18.18.pdf
new file mode 100644
index 0000000000000000000000000000000000000000..4f66c84365103b97b7c874b39fca597bd518fb96
GIT binary patch
literal 6022
zcmcJTc|6qX+sB3M*%cvUE$b|1#>kp2vSkY)h6W>MEW^l}Eqj)P$evw@L?V0Hx3V2+
z3R#jOWal@d<(%_6=l49%KhMm(zTdg8`}*F?=ep*a*Zmg0tfnCemXe_pu30YMrGo-M
z0IaPOoxD5%sDr{d;2Z%kqREgB0000r(9SrNJMr#}#G%wscG&AEIz>e~51cy+=|boI
zKv!Q|n*z-IVxS_`&Rz5T-Ro<0bcW~775R!QBt5YZlNc7;+03x2jt&j|+9AWGk!WXj
zW-h`rlzXtO5##0|)Zj-x6Xz)R>}#bGz`T_W^ntBjc~m&g>ZO}7c!HJl84ivJ7Zr$B
zMX7LjREqYO0H3;QtJ)bFb2CgBnkM^Y=c`|~>IsvuJN&kCsLw(81F}i4xZd2tnn0f;
z**M&u?A{eDFliPw6TDB8-V&eCGR{IDE80JK9AuS7+O9Y3x>4J-!t7jJt>kR%8o
z^D81mC*tSlWQgCB0f5FgT~Pp_zO9oH&gE$8pRttv^(0Ua06yx_K)ZY30MMV`|L6Eh
z8-d?+&
zJ*P@wrWSz&YMX;Z4Ht`=`o}vj7x5>I143T*mYP44NZr(5yL3!qskprEwwUcy!I|k|
zUWn6Z88)?&Qc2)otUb=U(W?V;tJ$2aRCBK#)^qw(J2MlrQkXY>%1(Ug4ED{G&;dW$
z0f^@EBd^GjJ?5Ny00VHegEId1;>~O(Tfta$khY15C
zQe8V6O^O9Q$EaF{#OqDBg)3Dv3;{jowa#{d-Fx?|+IxL0Z_M_%I6vZG;4*Z+?c5!2
zDb6CC`CpTNnpvdP5QsW#K>>(d$N(H&2~ii@uHNmj&PU#(A0dC2P~$5m=vW@)Q9
zPwtRWJ#w?TOFRd1nY}Xq)XmiIZUvLW_a)ymWXip|TKTceMsW;b=vAJqx-jW9#7%cX
zCd%4>*In`v<)VU*dKpJgGv#W0;doA4*;0gyw5hO7Zgp=w=iPMWag5^*Qw&45>We0~
z=cDzMSMDzYrA}wv%PjCXKRx|A+fkl!?>+9;0)oU#y;ceVy3O-#PAK_57vfr;*(k
zr#b7qTx{N#a!6#C^i~`+mXyqEDTZ|AnS#>C?yjE}7Jf%lmEXqyDM#zxG*
zZf|&SimMLSI@5ZSHEWB?M@94H*HJ@c614s<1gv?
zCnx1^)?c;cEvJyO%U8%aDQ>fdP=H^wY_^u?w?QqU&DFDb}JCI`8m3)d0^0KK&lm12e-9nis_;?y%X{BVM(9lR$zcUH{~lQzfru#>${pPHHqRtU(L)}rkoTXgr)_CZ()9S&Ba
zm&Dj(<3=jcnUQ#_+sRf8p(6?%6)vB4=a!7puZaiTHQD^^eB8uu762*!9
z^W}XmoRjI|@YrQkqYChQq<@3{*!<_{rRcA^3!WPySH-%ntK&BwPkt$Skbl38ZN%gf
zFs)lNaQzx#=X3JL($h^IL#CcI!
z_?*W2o_$r@v_6wDRVQ1w=dQdS2gAgx=;5-@~)jD
zlU2Hs<Z54}87fR(8Wf`tVA_~{a?R*{>d<2eu+xDo%
zU90yz7y*@vD!w(YROvOqN~H!0l!+u7Nd?Si)bKCyPAV#&KM$at6E6;aH$l16*wFT1
z@E8ysBx;Uz6;WZ$8%)x9p=nTkxbKKNon%r~Y~N^xk4hX)3_kUq{5inV^_u4NY3H~#
zx!rxQ&P0I-;nkpoQfh0oAG)`EZ|Q7BaaMI5;UJTCzrJ5mQttY(^%Ny1^Z`0GcZ`O+
z;#$DcGCts@gcI8dEZqm)Pyu0=SJ$sM>9Hi}0KirHN(7=hR$u^fJAue8LMD`=ffkEa2
z2{0}enQ!#Gv6-IOx#bSxBiR=nC3HV;%tgWb{7Y&4MLcUXLg
z5VdgE{y0pB4iQ@1@KH@nZO@=81hct!SZ3bngw0(&8?2vsTv}54k9$pfQyA+B+(eZ_;2%-!slm{_N
z_RL}1>-xvXk|}PdD@Vj`JhWcvk6!$pq8K7
zAKcB|4ZN4iGCJh6(d?^ssu;@TlyfFC1S1y6m@cq!R=rWfc#VH-=UV8QWYvAj*wj-`
zHV%aQ*s`Av6bHgqrz+)#6=UWFpD+#3b6;o1rmv
zwl=7~f3gLYYnbNG_}~`P#B0|Gt6=+a#wF-$6*}qR{kmjF*(UZJLW?R(*HtUYCbilG
zOp&mH{@~~E+zp9v$yTv4dya=W&5Sb=B~uJFwj2gtq1^&I>YmJ@xgIzhGq44XzBS7|q27eKgUqM*OrDoI{${;8ho9qM0axOc@W?PZKa9r2vblrtJp-$o$2nkkN{RzC%rD@8bWEG<
zmI~EabZ=5%ICv+5;CFs6JyGrut5^rqI#50ob(GVqYxG?de`H`p<}6C^0~wwTT(S15
zQGdvhr^~}0NHNk1rxRtfsd8nTTLE8|%nWvFpz&yDGk&MG%xnCvtm8m)I9Q-@*Gv^k
zzn!$W9KPsq02O6y820^Lv}P?0RcD9-OA_Ssh(Ls+?V(1)xZo49tW1N|
zC%pO_s1>6N^7#?|TwAp#_eQ#$4@v=z21Ky;w$IZg6A~(z>!L
z+UGgk#6SFz7HN@Ly((E;m+$bzl#3&)`hz`dqin>$*2*HnuY^9(v31lYzP4n%>gt@N
zlwZ|EchAAq!jh3&MpRs}
znYF`*4Y5)4N+HqK8Sig9ahcXe@k`%kf1Io~$~Yqkd$lbnHdsHzy01D^hXd?NL_1WkBMc0?Z~jowfyN}6+g3%OB{S@(SbuT
zOeJ*>8N`kEf})ssUVSY!JJYVtxR=RyN-E+5eY)EPhW@OAq-lA!e%k5JP=&0iu+QY#tcP{OJ-8QDb86V_E+>J#P3nlB9v?oTwudzn6xgc7CJH!;icp5Z2R*%W?eQmx)
z=%nykkCS$7V%ay?jgihCNN@H>ElA?rvE)9!9j(TKK%6bI)XawFTd-8`fXB+-v($^1
zW@SP8EFQEz7-o-`JKp_J9_{9rJD~J{2{C)!Rvm5ffwK0Pb+b%^JBv^Wg_Ey2z`Ai~
z@Z_7uxxO*6&)Ej2#P9GU?VJ$>CORecmrsoA#jw6UgO
zJ&nS)mJEK}`10Ei%HaZkEOTn_+s5U^CXW>eG|JXlMu9_>3g{obu{Rk~VKZYL%#E<;
z&}~mmisXkH^4UqB4lYV@w*0Exb^H96`Fi_V=$&1Ihh6RD54Da9R=HDhm^0C1-t~Vw
z7!cVaP^}O|&L2OZ5P%0o{_`|=bjbU89F&G4z`qZKf1Zke9rFNS5_kB&K?W;>9!wj6
zxnYgNSBEL#@!h(pPzjU8j&MceT0UhPw*;pckmA#e-X-2qRu
zR^RDUKn|)!jqAZ{jG}E`pzU-hj^R>byBk9xE8AmZ_R{
z%hUT%TxmC{d+Ag%SLC&S(f=3AAs(k8f06$esvu#9ADn;$8Prf7cJ63b9M=5@3Lu*F
zkS;`sa9KtFvYL^&8p;WI#nTAoj<)~ppn-HjJKqGH`_TtD>Jx^{p07yfAyQ-*Q
zy#W>gNg22-KvEhC2SC6e7yt|g$pWm7oV0LAXSCe~jDs@@06MZ<@UTM>;fE{)anvL&
zkkpnW@f8vwP(`|GqRWFmzrGO6dXB!Ouv6;Us4gmkj
z*wisZtcJ!o0Dz`w%ms`G`j_EoYE$%eoTCR(NNKQ)6hek5A1TQHUvGpAXtm0m}klvP8xx3nz^zEkm?|Wxxm$umTZxA}fV}
zKp{k@KWBo2AjCmHG6+(zKme!=LJ9SWVq>n=IZ@`L}Our$hNrJ(R
zRuFp_VOPArClxg~cO@f(o$m?2jzP_z+m{Ai6gHG3#JfiLT2OO`h30LXhetm@CCiX>
zvOu@8c9dh-wi64-@!_?a*P2XKqf+GYFJSlDs39~wtFqY{ixx~#@O0#ijqZrJ3)raY
zF;&v#OqyP)cX&)j0mY+7pQU2mBOiP6#0{89`rG|s=o4%HtY7V^(2IpI_wFpUgL7)~
z_xCzlDJ;VGL!O+UrRkztDKFK)^fA5S@T;=CRris-enSFp_IAVf#tx%8%WY8H8H$X-
z$l`mCmV#62^|m;8?Du5}#0t|ovAU`UMAr?z46~EajPzz&^1%OE@dz2%;188Ssvvrsi85A9KObrBv
zyo7*2kQEAA4SYN&b-Zvd<#Z-FtB#_w%It}Vdo)6nxyouR@yrd!1r$|ukd!RFF}5F-
l!H*TGsK{pXXfyt~a}ONS9p~*%+!Rbk21+L^tgf#?_a7qEC&T~%
literal 0
HcmV?d00001
diff --git a/rmcs_ws/src/rmcs_bringup/config/flight.yaml b/rmcs_ws/src/rmcs_bringup/config/flight.yaml
index 151db7db..56a182e7 100644
--- a/rmcs_ws/src/rmcs_bringup/config/flight.yaml
+++ b/rmcs_ws/src/rmcs_bringup/config/flight.yaml
@@ -7,7 +7,7 @@ rmcs_executor:
- rmcs_core::controller::gimbal::SimpleGimbalController -> gimbal_controller
- rmcs_core::controller::pid::ErrorPidController -> yaw_angle_pid_controller
- - rmcs_core::controller::pid::ErrorPidController -> yaw_velocity_pid_controller
+ #- rmcs_core::controller::pid::PidController -> yaw_velocity_pid_controller
- rmcs_core::controller::pid::ErrorPidController -> pitch_angle_pid_controller
- rmcs_core::controller::shooting::FrictionWheelController -> friction_wheel_controller
@@ -17,8 +17,6 @@ rmcs_executor:
- rmcs_core::controller::pid::PidController -> right_friction_velocity_pid_controller
- rmcs_core::controller::pid::PidController -> bullet_feeder_velocity_pid_controller
- # - rmcs_core::broadcaster::TfBroadcaster -> tf_broadcaster
-
- rmcs_core::referee::command::Interaction -> referee_interaction
#- rmcs_core::referee::command::interaction::Ui -> referee_ui
#- rmcs_core::referee::app::ui::Flight -> referee_ui_flight
@@ -29,10 +27,19 @@ rmcs_executor:
# - rmcs_auto_aim::AutoAimController -> auto_aim_controller
- rmcs_core::broadcaster::ValueBroadcaster -> value_broadcaster
+ - rmcs_core::broadcaster::TfBroadcaster -> tf_broadcaster
value_broadcaster:
ros__parameters:
forward_list:
+ - /gimbal/pitch/angle
+ - /gimbal/pitch/velocity
+ - /gimbal/pitch/torque
+ - /gimbal/pitch/control_torque
+ - /gimbal/pitch/control_angle_error
+ - /gimbal/pitch/control_velocity
+ - /gimbal/pitch/velocity_imu
+
- /gimbal/yaw/angle
- /gimbal/yaw/velocity
- /gimbal/yaw/torque
@@ -40,11 +47,15 @@ value_broadcaster:
- /gimbal/yaw/control_angle_error
- /gimbal/yaw/control_velocity
+tf_broadcaster:
+ ros__parameters:
+ tf: /tf
+
flight_hardware:
ros__parameters:
usb_pid: -1
- yaw_motor_zero_point: 5450
- pitch_motor_zero_point: 30473
+ yaw_motor_zero_point: 5807
+ pitch_motor_zero_point: 29303
referee_status:
ros__parameters:
@@ -52,24 +63,16 @@ referee_status:
gimbal_controller:
ros__parameters:
- upper_limit: -0.249
- lower_limit: 0.249
- yaw_upper_limit: -180.0
- yaw_lower_limit: 180.0
+ upper_limit: -0.349
+ lower_limit: 0.349
+ yaw_upper_limit: -0.5
+ yaw_lower_limit: 0.5
yaw_angle_pid_controller:
ros__parameters:
measurement: /gimbal/yaw/control_angle_error
control: /gimbal/yaw/control_velocity
- kp: 1.0
- ki: 0.0
- kd: 0.0
-
-yaw_velocity_pid_controller:
- ros__parameters:
- measurement: /gimbal/yaw/control_velocity
- control: /gimbal/yaw/control_torque
- kp: 1.0
+ kp: 0.5
ki: 0.0
kd: 0.0
@@ -77,7 +80,7 @@ pitch_angle_pid_controller:
ros__parameters:
measurement: /gimbal/pitch/control_angle_error
control: /gimbal/pitch/control_velocity
- kp: 16.0
+ kp: 6.0
ki: 0.0
kd: 0.0
diff --git a/rmcs_ws/src/rmcs_core/plugins.xml b/rmcs_ws/src/rmcs_core/plugins.xml
index 4d3bb141..02efadb1 100644
--- a/rmcs_ws/src/rmcs_core/plugins.xml
+++ b/rmcs_ws/src/rmcs_core/plugins.xml
@@ -71,6 +71,9 @@
Test plugin.
+
+ Dynamic TF publisher for gimbal coordinate frames
+
Test plugin.
diff --git a/rmcs_ws/src/rmcs_core/src/controller/gimbal/simple_gimbal_controller.cpp b/rmcs_ws/src/rmcs_core/src/controller/gimbal/simple_gimbal_controller.cpp
index 19bdbaa8..925db272 100644
--- a/rmcs_ws/src/rmcs_core/src/controller/gimbal/simple_gimbal_controller.cpp
+++ b/rmcs_ws/src/rmcs_core/src/controller/gimbal/simple_gimbal_controller.cpp
@@ -62,14 +62,15 @@ class SimpleGimbalController
if (!two_axis_gimbal_solver.enabled())
return two_axis_gimbal_solver.update(TwoAxisGimbalSolver::SetToLevel());
- constexpr double joystick_sensitivity = 0.06;
+ constexpr double joystick_sensitivity = 0.006;
constexpr double mouse_sensitivity = 0.5;
double yaw_shift =
joystick_sensitivity * joystick_left_->y() + mouse_sensitivity * mouse_velocity_->y();
- RCLCPP_INFO(get_logger(), "%lf",yaw_shift);
+ // RCLCPP_INFO(get_logger(), "%lf",yaw_shift);
double pitch_shift =
-joystick_sensitivity * joystick_left_->x() - mouse_sensitivity * mouse_velocity_->x();
+ RCLCPP_INFO(get_logger(),"%lf",pitch_shift);
return two_axis_gimbal_solver.update(
TwoAxisGimbalSolver::SetControlShift(yaw_shift, pitch_shift));
diff --git a/rmcs_ws/src/rmcs_core/src/hardware/flight.cpp b/rmcs_ws/src/rmcs_core/src/hardware/flight.cpp
index 96c836a8..ec4c6a8b 100644
--- a/rmcs_ws/src/rmcs_core/src/hardware/flight.cpp
+++ b/rmcs_ws/src/rmcs_core/src/hardware/flight.cpp
@@ -42,7 +42,8 @@ class Flight
, transmit_buffer_(*this, 32)
, event_thread_([this]() { handle_events(); }) {
gimbal_yaw_motor_.configure(
- device::LkMotor::Config{device::LkMotor::Type::MHF7015}.set_encoder_zero_point(
+ device::LkMotor::Config{device::LkMotor::Type::MHF7015}
+ .set_encoder_zero_point(
static_cast(get_parameter("yaw_motor_zero_point").as_int())));
gimbal_pitch_motor_.configure(
device::LkMotor::Config{device::LkMotor::Type::MG4010E_I10}.set_encoder_zero_point(
@@ -81,7 +82,7 @@ class Flight
constexpr double gimbal_center_x = 0;
constexpr double gimbal_center_y = 0;
- constexpr double gimbal_center_z = 0.20552;
+ constexpr double gimbal_center_z = -0.20552;
tf_->set_transform(
Eigen::Translation3d{gimbal_center_x, gimbal_center_y, gimbal_center_z});
@@ -120,8 +121,8 @@ class Flight
transmit_buffer_.add_can2_transmission(0x144, gimbal_pitch_motor_.generate_command());
can_commands[0] = gimbal_bullet_feeder_.generate_command();
- can_commands[1] = gimbal_left_friction_.generate_command();
- can_commands[2] = gimbal_right_friction_.generate_command();
+ can_commands[1] = gimbal_right_friction_.generate_command();
+ can_commands[2] = gimbal_left_friction_.generate_command();
can_commands[3] = 0;
transmit_buffer_.add_can2_transmission(0x200, std::bit_cast(can_commands));
}
@@ -140,8 +141,8 @@ class Flight
gimbal_right_friction_.update_status();
}
- void update_imu() {
- bmi088_.update_status();
+ void update_imu() {
+ bmi088_.update_status();
Eigen::Quaterniond gimbal_imu_pose{bmi088_.q0(), bmi088_.q1(), bmi088_.q2(), bmi088_.q3()};
tf_->set_transform(
gimbal_imu_pose.conjugate());
@@ -177,9 +178,9 @@ class Flight
return;
if (can_id == 0x201) {
gimbal_bullet_feeder_.store_status(can_data);
- } else if (can_id == 0x202) {
- gimbal_left_friction_.store_status(can_data);
} else if (can_id == 0x203) {
+ gimbal_left_friction_.store_status(can_data);
+ } else if (can_id == 0x202) {
gimbal_right_friction_.store_status(can_data);
} else if (can_id == 0x144) {
gimbal_pitch_motor_.store_status(can_data);
@@ -227,6 +228,7 @@ class Flight
OutputInterface gimbal_yaw_velocity_imu_;
OutputInterface gimbal_pitch_velocity_imu_;
+
OutputInterface tf_;
From b50b39f62f41a90c3db81af12a25276d1fec5fc5 Mon Sep 17 00:00:00 2001
From: 1Feishu <1291113686@qq.com>
Date: Wed, 3 Dec 2025 17:56:49 +0800
Subject: [PATCH 4/7] update librmcs submodule pointer
---
rmcs_ws/src/rmcs_core/librmcs | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/rmcs_ws/src/rmcs_core/librmcs b/rmcs_ws/src/rmcs_core/librmcs
index b82f2eaf..80444ec9 160000
--- a/rmcs_ws/src/rmcs_core/librmcs
+++ b/rmcs_ws/src/rmcs_core/librmcs
@@ -1 +1 @@
-Subproject commit b82f2eafd21371a23d046e5f75884fe6c6e49124
+Subproject commit 80444ec9251a83e31bc153fe06cf91ddb5eece37
From c2e3934076e8f51c5614469d983d7105acc089c3 Mon Sep 17 00:00:00 2001
From: 1Feishu <1291113686@qq.com>
Date: Tue, 16 Dec 2025 19:30:07 +0800
Subject: [PATCH 5/7] add MHF7015
---
rmcs_ws/src/rmcs_bringup/config/flight.yaml | 38 +++-
rmcs_ws/src/rmcs_core/plugins.xml | 3 +
.../gimbal/GimbalFrequencySweep.cpp | 197 ++++++++++++++++++
.../gimbal/simple_gimbal_controller.cpp | 2 -
.../gimbal/two_axis_gimbal_solver.hpp | 23 +-
rmcs_ws/src/rmcs_core/src/hardware/flight.cpp | 25 ++-
6 files changed, 260 insertions(+), 28 deletions(-)
create mode 100644 rmcs_ws/src/rmcs_core/src/controller/gimbal/GimbalFrequencySweep.cpp
diff --git a/rmcs_ws/src/rmcs_bringup/config/flight.yaml b/rmcs_ws/src/rmcs_bringup/config/flight.yaml
index 56a182e7..cf8ef4eb 100644
--- a/rmcs_ws/src/rmcs_bringup/config/flight.yaml
+++ b/rmcs_ws/src/rmcs_bringup/config/flight.yaml
@@ -7,8 +7,10 @@ rmcs_executor:
- rmcs_core::controller::gimbal::SimpleGimbalController -> gimbal_controller
- rmcs_core::controller::pid::ErrorPidController -> yaw_angle_pid_controller
- #- rmcs_core::controller::pid::PidController -> yaw_velocity_pid_controller
+ - rmcs_core::controller::pid::PidController -> yaw_velocity_pid_controller
- rmcs_core::controller::pid::ErrorPidController -> pitch_angle_pid_controller
+ #- rmcs_core::controller::gimbal::GimbalFrequencySweep -> gimbal_frequency
+
- rmcs_core::controller::shooting::FrictionWheelController -> friction_wheel_controller
- rmcs_core::controller::shooting::HeatController -> heat_controller
@@ -54,8 +56,8 @@ tf_broadcaster:
flight_hardware:
ros__parameters:
usb_pid: -1
- yaw_motor_zero_point: 5807
- pitch_motor_zero_point: 29303
+ yaw_motor_zero_point: 4608
+ pitch_motor_zero_point: 51629
referee_status:
ros__parameters:
@@ -63,27 +65,43 @@ referee_status:
gimbal_controller:
ros__parameters:
- upper_limit: -0.349
- lower_limit: 0.349
- yaw_upper_limit: -0.5
- yaw_lower_limit: 0.5
+ upper_limit: -0.149
+ lower_limit: 0.149
+ yaw_upper_limit: -0.349
+ yaw_lower_limit: 0.349
yaw_angle_pid_controller:
ros__parameters:
measurement: /gimbal/yaw/control_angle_error
control: /gimbal/yaw/control_velocity
- kp: 0.5
+ kp: 8.0
ki: 0.0
- kd: 0.0
+ kd: 0.0003
+
+yaw_velocity_pid_controller:
+ ros__parameters:
+ measurement: /gimbal/yaw/velocity_imu
+ setpoint: /gimbal/yaw/control_velocity
+ control: /gimbal/yaw/control_torque
+ kp: 1.5
+ ki: 0.0
+ kd: 0.01
pitch_angle_pid_controller:
ros__parameters:
measurement: /gimbal/pitch/control_angle_error
control: /gimbal/pitch/control_velocity
- kp: 6.0
+ kp: 16.0
ki: 0.0
kd: 0.0
+# gimbal_frequency:
+# ros__parameters:
+# F_start: 5
+# F_end: 50
+# Repeat_time: 20
+
+
friction_wheel_controller:
ros__parameters:
friction_wheels:
diff --git a/rmcs_ws/src/rmcs_core/plugins.xml b/rmcs_ws/src/rmcs_core/plugins.xml
index 02efadb1..3a54e23b 100644
--- a/rmcs_ws/src/rmcs_core/plugins.xml
+++ b/rmcs_ws/src/rmcs_core/plugins.xml
@@ -38,6 +38,9 @@
Test plugin.
+
+ Test plugin.
+
Test plugin.
diff --git a/rmcs_ws/src/rmcs_core/src/controller/gimbal/GimbalFrequencySweep.cpp b/rmcs_ws/src/rmcs_core/src/controller/gimbal/GimbalFrequencySweep.cpp
new file mode 100644
index 00000000..701d3ddc
--- /dev/null
+++ b/rmcs_ws/src/rmcs_core/src/controller/gimbal/GimbalFrequencySweep.cpp
@@ -0,0 +1,197 @@
+// #include
+// #include
+// #include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include // 用于时间格式化
+#include // 添加文件流支持
+#include // 添加格式化支持
+#include // 用于创建目录
+
+namespace rmcs_core::controller::gimbal {
+
+using namespace rmcs_description;
+
+class GimbalFrequencySweep
+ : public rmcs_executor::Component
+ , public rclcpp::Node {
+public:
+ GimbalFrequencySweep()
+ : Node("gimbal_frequency_sweep") {
+ // 创建数据存储目录
+ create_data_directory();
+ // 初始化CSV文件
+ init_csv_file();
+
+ register_input("/remote/switch/right", switch_right_);
+
+ register_input("/remote/switch/left", switch_left_);
+ register_input("/gimbal/yaw/velocity", yaw_velocity_);
+ register_input("/gimbal/yaw/max_torque", yaw_max_torque_);
+
+ register_output("/gimbal/yaw/control_torque", yaw_control_torque_);
+
+ // 参数配置
+ }
+
+ ~GimbalFrequencySweep() {
+ if (csv_file_.is_open()) {
+ csv_file_.close();
+ RCLCPP_INFO(get_logger(), "CSV file closed: %s", filename_.c_str());
+ }
+ }
+
+ void update() override {
+ using namespace rmcs_msgs;
+
+ auto switch_right = *switch_right_;
+ auto switch_left = *switch_left_;
+
+ do {
+ if (switch_left == Switch::DOWN && switch_right == Switch::MIDDLE) {
+
+ Now_time = this->now();
+ if (f_now > F_end) {
+ break;
+ }
+ if (last_time <= 0.0002) {
+ last_time = Now_time.seconds();
+ }
+ now_time = Now_time.seconds();
+
+ current = Top * std::sin(2 * Pi * f_now * (now_time - last_time));
+ double torque_command = current * k;
+ *yaw_control_torque_ = torque_command;
+ if ((now_time - last_time) > ((1 / f_now) * Repeat_time)) {
+ if (f_now < 24) {
+ f_now += 0.5;
+ } else if (f_now >= 24 && f_now <= 120) {
+ f_now += 2;
+ } else {
+ f_now += 4;
+ }
+ last_time = Now_time.seconds();
+ }
+ record_data(); // gimbal_yaw_motor_.control_torque()
+ }
+ if (switch_left == Switch::DOWN && switch_right == Switch::DOWN) {
+ reset_status();
+ }
+
+ } while (false);
+ }
+
+private:
+ void create_data_directory() {
+ // 获取当前用户的主目录
+ const char* home_dir = std::getenv("HOME");
+ if (!home_dir) {
+ RCLCPP_ERROR(get_logger(), "Failed to get home directory");
+ return;
+ }
+
+ // 创建数据目录
+ data_dir_ = std::string(home_dir) + "/gimbal_sweep_data";
+ if (mkdir(data_dir_.c_str(), 0777) == -1) {
+ if (errno != EEXIST) {
+ RCLCPP_ERROR(get_logger(), "Failed to create data directory: %s", strerror(errno));
+ } else {
+ RCLCPP_INFO(get_logger(), "Using existing data directory: %s", data_dir_.c_str());
+ }
+ } else {
+ RCLCPP_INFO(get_logger(), "Created data directory: %s", data_dir_.c_str());
+ }
+ }
+
+ void init_csv_file() {
+ // 生成带时间戳的文件名
+ auto now = std::time(nullptr);
+ std::tm now_tm = *std::localtime(&now);
+
+ std::ostringstream oss;
+ oss << data_dir_ << "/sweep_" << std::put_time(&now_tm, "%Y%m%d_%H%M%S") << ".csv";
+ filename_ = oss.str();
+
+ csv_file_.open(filename_, std::ios::out);
+ if (!csv_file_.is_open()) {
+ RCLCPP_ERROR(get_logger(), "Failed to open CSV file: %s", filename_.c_str());
+ return;
+ }
+
+ // 写入CSV表头
+ csv_file_ << "actual_velocity control_torque\n";
+ csv_file_.flush();
+
+ RCLCPP_INFO(get_logger(), "Data recording started. File: %s", filename_.c_str());
+ }
+
+ void record_data() {
+ if (!csv_file_.is_open())
+ return;
+
+ // 获取当前时间
+ auto now = this->now();
+ // double elapsed = (last_time > 0) ? now.seconds() - last_time : 0.0;
+
+ // 写入数据
+ csv_file_ << *yaw_velocity_ << " " << current << "\n";
+ RCLCPP_INFO(get_logger(), "%d", i++);
+ // 定期刷新缓冲区以确保
+ static int count = 0;
+ if (++count % 100 == 0) {
+ csv_file_.flush();
+ }
+ }
+
+ void reset_status() {
+ f_now = 1.0;
+ *yaw_control_torque_ = 0.0;
+ }
+
+ rclcpp::Time Now_time;
+
+ double now_time;
+ double last_time = 0.0;
+ double current;
+
+ float f_now = 5.0;
+ int i = 0;
+
+ static constexpr int F_start = 5;
+ static constexpr int F_end = 50;
+ static constexpr int Repeat_time = 20;
+ static constexpr double Pi = 3.1415926;
+ static constexpr double Top = 0.999;
+ static constexpr double k = 0.1;
+ // ROS接口
+
+ rclcpp::TimerBase::SharedPtr control_timer_;
+
+ // 数据接口
+ InputInterface yaw_velocity_;
+ InputInterface yaw_max_torque_;
+ OutputInterface yaw_current_command_;
+ OutputInterface yaw_control_torque_;
+
+ InputInterface switch_right_;
+ InputInterface switch_left_;
+
+ std::string data_dir_;
+ std::string filename_;
+ std::ofstream csv_file_;
+};
+} // namespace rmcs_core::controller::gimbal
+
+#include
+
+PLUGINLIB_EXPORT_CLASS(
+ rmcs_core::controller::gimbal::GimbalFrequencySweep, rmcs_executor::Component)
\ No newline at end of file
diff --git a/rmcs_ws/src/rmcs_core/src/controller/gimbal/simple_gimbal_controller.cpp b/rmcs_ws/src/rmcs_core/src/controller/gimbal/simple_gimbal_controller.cpp
index 925db272..517dc0fc 100644
--- a/rmcs_ws/src/rmcs_core/src/controller/gimbal/simple_gimbal_controller.cpp
+++ b/rmcs_ws/src/rmcs_core/src/controller/gimbal/simple_gimbal_controller.cpp
@@ -67,10 +67,8 @@ class SimpleGimbalController
double yaw_shift =
joystick_sensitivity * joystick_left_->y() + mouse_sensitivity * mouse_velocity_->y();
- // RCLCPP_INFO(get_logger(), "%lf",yaw_shift);
double pitch_shift =
-joystick_sensitivity * joystick_left_->x() - mouse_sensitivity * mouse_velocity_->x();
- RCLCPP_INFO(get_logger(),"%lf",pitch_shift);
return two_axis_gimbal_solver.update(
TwoAxisGimbalSolver::SetControlShift(yaw_shift, pitch_shift));
diff --git a/rmcs_ws/src/rmcs_core/src/controller/gimbal/two_axis_gimbal_solver.hpp b/rmcs_ws/src/rmcs_core/src/controller/gimbal/two_axis_gimbal_solver.hpp
index ae590f10..b218e27f 100644
--- a/rmcs_ws/src/rmcs_core/src/controller/gimbal/two_axis_gimbal_solver.hpp
+++ b/rmcs_ws/src/rmcs_core/src/controller/gimbal/two_axis_gimbal_solver.hpp
@@ -1,5 +1,6 @@
#pragma once
+#include "librmcs/utility/logging.hpp"
#include
#include
@@ -26,11 +27,13 @@ class TwoAxisGimbalSolver {
};
public:
- TwoAxisGimbalSolver(rmcs_executor::Component& component, double upper_limit, double lower_limit,double yaw_upper_limit, double yaw_lower_limit)
+ TwoAxisGimbalSolver(
+ rmcs_executor::Component& component, double upper_limit, double lower_limit,
+ double yaw_upper_limit, double yaw_lower_limit)
: upper_limit_(std::cos(upper_limit), -std::sin(upper_limit))
- , lower_limit_(std::cos(lower_limit), -std::sin(lower_limit))
- , yaw_upper_limit_(std::cos(yaw_upper_limit),-std::sin(yaw_upper_limit))
- , yaw_lower_limit_(std::cos(yaw_lower_limit),-std::sin(yaw_lower_limit)){
+ , lower_limit_(std::cos(lower_limit), -std::sin(lower_limit))
+ , yaw_upper_limit_(std::cos(yaw_upper_limit), -std::sin(yaw_upper_limit))
+ , yaw_lower_limit_(std::cos(yaw_lower_limit), -std::sin(yaw_lower_limit)) {
component.register_input("/gimbal/pitch/angle", gimbal_pitch_angle_);
component.register_input("/gimbal/yaw/angle", gimbal_yaw_angle_);
@@ -107,6 +110,11 @@ class TwoAxisGimbalSolver {
update_yaw_axis();
PitchLink::DirectionVector control_direction = operation.update(*this);
+ // LOG_INFO(
+ // "x: %f, y: %f, z: %f", control_direction->x(), control_direction->y(),
+ // control_direction->z());
+
+
if (!control_enabled_)
return {nan_, nan_};
@@ -116,6 +124,7 @@ class TwoAxisGimbalSolver {
if (!control_enabled_)
return {nan_, nan_};
+
control_direction_ =
fast_tf::cast(yaw_link_to_pitch_link(control_direction_yaw_link, pitch), *tf_);
return calculate_control_errors(control_direction_yaw_link, pitch);
@@ -171,7 +180,7 @@ class TwoAxisGimbalSolver {
else if (z < lower_limit_.y())
*control_direction << lower_limit_.x() * projection, lower_limit_.y();
- const auto& [x_,y_,z_] = *control_direction;
+ const auto& [x_,y_,z_] = *control_direction;
Eigen::Vector2d yaw_projection{x_,y_};
double yaw_norm = yaw_projection.norm();
@@ -189,6 +198,7 @@ class TwoAxisGimbalSolver {
}
+
static AngleError calculate_control_errors(
const YawLink::DirectionVector& control_direction, const Eigen::Vector2d& pitch) {
const auto& [x, y, z] = *control_direction;
@@ -199,6 +209,9 @@ class TwoAxisGimbalSolver {
double x_projected = std::sqrt(x * x + y * y);
result.pitch_angle_error = -std::atan2(z * c - x_projected * s, z * s + x_projected * c);
+ // LOG_INFO("x: %f, y: %f, z: %f, yaw err: %f, pitch err: %f",x, y,
+ // z,result.yaw_angle_error,result.pitch_angle_error);
+
return result;
}
diff --git a/rmcs_ws/src/rmcs_core/src/hardware/flight.cpp b/rmcs_ws/src/rmcs_core/src/hardware/flight.cpp
index ec4c6a8b..5d741135 100644
--- a/rmcs_ws/src/rmcs_core/src/hardware/flight.cpp
+++ b/rmcs_ws/src/rmcs_core/src/hardware/flight.cpp
@@ -26,7 +26,9 @@ class Flight
, private librmcs::client::CBoard {
public:
Flight()
- : Node{get_component_name(), rclcpp::NodeOptions{}.automatically_declare_parameters_from_overrides(true)}
+ : Node{
+ get_component_name(),
+ rclcpp::NodeOptions{}.automatically_declare_parameters_from_overrides(true)}
, librmcs::client::CBoard{static_cast(get_parameter("usb_pid").as_int())}
, logger_(get_logger())
, flight_command_(
@@ -42,8 +44,7 @@ class Flight
, transmit_buffer_(*this, 32)
, event_thread_([this]() { handle_events(); }) {
gimbal_yaw_motor_.configure(
- device::LkMotor::Config{device::LkMotor::Type::MHF7015}
- .set_encoder_zero_point(
+ device::LkMotor::Config{device::LkMotor::Type::MHF7015}.set_reversed().set_encoder_zero_point(
static_cast(get_parameter("yaw_motor_zero_point").as_int())));
gimbal_pitch_motor_.configure(
device::LkMotor::Config{device::LkMotor::Type::MG4010E_I10}.set_encoder_zero_point(
@@ -54,7 +55,7 @@ class Flight
.set_reduction_ratio(1.));
gimbal_right_friction_.configure(
device::DjiMotor::Config{device::DjiMotor::Type::M3508}
-
+
.set_reduction_ratio(1.));
gimbal_bullet_feeder_.configure(
device::DjiMotor::Config{device::DjiMotor::Type::M2006}.enable_multi_turn_angle());
@@ -112,19 +113,22 @@ class Flight
update_motors();
update_imu();
dr16_.update_status();
+
}
void command_update() {
uint16_t can_commands[4];
- transmit_buffer_.add_can1_transmission(0x141, gimbal_yaw_motor_.generate_command());
- transmit_buffer_.add_can2_transmission(0x144, gimbal_pitch_motor_.generate_command());
+ transmit_buffer_.add_can1_transmission(0x141, gimbal_yaw_motor_.generate_torque_command());
+ transmit_buffer_.add_can2_transmission(0x144, gimbal_pitch_motor_.generate_command());
can_commands[0] = gimbal_bullet_feeder_.generate_command();
can_commands[1] = gimbal_right_friction_.generate_command();
can_commands[2] = gimbal_left_friction_.generate_command();
can_commands[3] = 0;
transmit_buffer_.add_can2_transmission(0x200, std::bit_cast(can_commands));
+
+ transmit_buffer_.trigger_transmission();
}
private:
@@ -141,13 +145,13 @@ class Flight
gimbal_right_friction_.update_status();
}
- void update_imu() {
- bmi088_.update_status();
+ void update_imu() {
+ bmi088_.update_status();
Eigen::Quaterniond gimbal_imu_pose{bmi088_.q0(), bmi088_.q1(), bmi088_.q2(), bmi088_.q3()};
tf_->set_transform(
gimbal_imu_pose.conjugate());
- *gimbal_yaw_velocity_imu_ = bmi088_.gz();
+ *gimbal_yaw_velocity_imu_ = bmi088_.gz();
*gimbal_pitch_velocity_imu_ = bmi088_.gy();
}
void gimbal_calibrate_subscription_callback(std_msgs::msg::Int32::UniquePtr) {
@@ -168,7 +172,7 @@ class Flight
if (can_id == 0x141) {
gimbal_yaw_motor_.store_status(can_data);
- }
+ }
}
void can2_receive_callback(
@@ -228,7 +232,6 @@ class Flight
OutputInterface gimbal_yaw_velocity_imu_;
OutputInterface gimbal_pitch_velocity_imu_;
-
OutputInterface tf_;
From 721d62df019fa38cde7fe2a56c925f8af076ee39 Mon Sep 17 00:00:00 2001
From: 1Feishu <1291113686@qq.com>
Date: Mon, 29 Dec 2025 17:01:42 +0800
Subject: [PATCH 6/7] new
---
.../rmcs_core/src/controller/gimbal/GimbalFrequencySweep.cpp | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
diff --git a/rmcs_ws/src/rmcs_core/src/controller/gimbal/GimbalFrequencySweep.cpp b/rmcs_ws/src/rmcs_core/src/controller/gimbal/GimbalFrequencySweep.cpp
index 701d3ddc..e661b0b0 100644
--- a/rmcs_ws/src/rmcs_core/src/controller/gimbal/GimbalFrequencySweep.cpp
+++ b/rmcs_ws/src/rmcs_core/src/controller/gimbal/GimbalFrequencySweep.cpp
@@ -163,10 +163,10 @@ class GimbalFrequencySweep
double last_time = 0.0;
double current;
- float f_now = 5.0;
+ float f_now = 1.0;
int i = 0;
- static constexpr int F_start = 5;
+ static constexpr int F_start = 1;
static constexpr int F_end = 50;
static constexpr int Repeat_time = 20;
static constexpr double Pi = 3.1415926;
From f7ecebfbb4e33d86a2c50b934d211f06efb70316 Mon Sep 17 00:00:00 2001
From: 1Feishu <1291113686@qq.com>
Date: Sun, 4 Jan 2026 20:06:15 +0800
Subject: [PATCH 7/7] delete *.gv *.pdf
---
frames_2025-11-27_16.09.16.gv | 1 -
frames_2025-11-27_16.09.16.pdf | Bin 6023 -> 0 bytes
frames_2025-11-27_16.24.56.gv | 1 -
frames_2025-11-27_16.24.56.pdf | Bin 6022 -> 0 bytes
frames_2025-11-27_16.25.48.gv | 1 -
frames_2025-11-27_16.25.48.pdf | Bin 6022 -> 0 bytes
frames_2025-11-27_16.27.10.gv | 1 -
frames_2025-11-27_16.27.10.pdf | Bin 6021 -> 0 bytes
frames_2025-12-02_19.18.18.gv | 1 -
frames_2025-12-02_19.18.18.pdf | Bin 6022 -> 0 bytes
rmcs_ws/src/rmcs_bringup/config/flight.yaml | 9 -
rmcs_ws/src/rmcs_core/plugins.xml | 3 -
.../gimbal/GimbalFrequencySweep.cpp | 197 ------------------
13 files changed, 214 deletions(-)
delete mode 100644 frames_2025-11-27_16.09.16.gv
delete mode 100644 frames_2025-11-27_16.09.16.pdf
delete mode 100644 frames_2025-11-27_16.24.56.gv
delete mode 100644 frames_2025-11-27_16.24.56.pdf
delete mode 100644 frames_2025-11-27_16.25.48.gv
delete mode 100644 frames_2025-11-27_16.25.48.pdf
delete mode 100644 frames_2025-11-27_16.27.10.gv
delete mode 100644 frames_2025-11-27_16.27.10.pdf
delete mode 100644 frames_2025-12-02_19.18.18.gv
delete mode 100644 frames_2025-12-02_19.18.18.pdf
delete mode 100644 rmcs_ws/src/rmcs_core/src/controller/gimbal/GimbalFrequencySweep.cpp
diff --git a/frames_2025-11-27_16.09.16.gv b/frames_2025-11-27_16.09.16.gv
deleted file mode 100644
index 545c92c6..00000000
--- a/frames_2025-11-27_16.09.16.gv
+++ /dev/null
@@ -1 +0,0 @@
-digraph G { "No tf data received" }
\ No newline at end of file
diff --git a/frames_2025-11-27_16.09.16.pdf b/frames_2025-11-27_16.09.16.pdf
deleted file mode 100644
index 829e93354c7f484d29c422182fb068b640f6a7f9..0000000000000000000000000000000000000000
GIT binary patch
literal 0
HcmV?d00001
literal 6023
zcmcJTc|6qX+sADwOSYj18EaW*F*8QiY}sYY9z%oCn6Zo{BeG@Rh3rdqAu19fOV&uo
zb|fWPk|Jd1nbC62dHv3_{PWCrUNduF_w~J(&vkvTdEIZ}%W4{u5GfgY;YZ6=yYw(1
z7>Kubp_i8jf^^Y1CxSB&PBIzM1A#!01_nz&dyu}dC<0my?SQ|ArdL#?_au0rQLgm9
zS$YOKI@A!BXM@%04j!5plCP~b&>NjUUrH2LNO@=_CNV6wvzcvE7abb|BIbDEClhGtS*psL7w|L%g%xldm;OK#S)9@Owa`@~CjUO_#ecWP*+J2?2o&7Zr$B
zMXPXl)`-3=2R(MvQFSmf;bxpLGE4Q(D^kB~(-$V;aQJQI(12t5Pv|Ct;(BWvTOvcg
zWb<%Gsz*<-z@&N9hv5AanQaM)ZR5-}W`h}ZJ42s2TmXNhA*9Ms!O}{Y4fy?eNNfU!iK57u6e~N8_&j+%@SJSue6k%$_>b`_a#srdfKzVtxf%F2Qz@!Ecqdk-APqc@@HcNqNw6ds
zDDx{KBq!4Q=VZv=lL0{{H{8%bkb%96F~Rj{>YuTc{dFfu9|$?>(7
zN*jaUMa@Nhq@tijQri5d2;|X!iU2|US{4NIw{`to1_b(h9sib7WL&H1T`<
z-8$mqFJ+sbM#uK28tZYUl++Z052=EQof&8^J}z6_@u9$zK=}syc0Zp>?>4w8iaRN=
zW?oa}a5JmG>Em_>NgA$Jj~XBBbS?UvGzkdl>aVbPB9Xpnu%=BZu~b&oa9hlNs`%_o
z886gjv=X0QL!%^cFxC-o+w9#5z13<#QK7ll0q;BWse^@?MJdeJXUai*=`8+_DWL;?
ziUaV8%lEw_NA_6q?*I)U(N4-fw-;{|0fXzS1KoJK_e1tW6rT<_^sSG}j|jw6w%pW+9n!R^~TbJvuZ+@|P>iurW%Q
z&(3f*c)QxYtKg8xEAOv9Xf7|G*HR4WDKrCTjwP?35f*-XqPD1=|5Lu!xz9c(!kV?Q
zAGv)I!D()~TB*nQ
z!_Cbp&2^0s?2``PvJtlQL3}HKPl`9XHRyfA_f!MC7WfSMR1eIJ-fLbGo4CX7?h