lidar_fusion_node.cpp 147 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600160116021603160416051606160716081609161016111612161316141615161616171618161916201621162216231624162516261627162816291630163116321633163416351636163716381639164016411642164316441645164616471648164916501651165216531654165516561657165816591660166116621663166416651666166716681669167016711672167316741675167616771678167916801681168216831684168516861687168816891690169116921693169416951696169716981699170017011702170317041705170617071708170917101711171217131714171517161717171817191720172117221723172417251726172717281729173017311732173317341735173617371738173917401741174217431744174517461747174817491750175117521753175417551756175717581759176017611762176317641765176617671768176917701771177217731774177517761777177817791780178117821783178417851786178717881789179017911792179317941795179617971798179918001801180218031804180518061807180818091810181118121813181418151816181718181819182018211822182318241825182618271828182918301831183218331834183518361837183818391840184118421843184418451846184718481849185018511852185318541855185618571858185918601861186218631864186518661867186818691870187118721873187418751876187718781879188018811882188318841885188618871888188918901891189218931894189518961897189818991900190119021903190419051906190719081909191019111912191319141915191619171918191919201921192219231924192519261927192819291930193119321933193419351936193719381939194019411942194319441945194619471948194919501951195219531954195519561957195819591960196119621963196419651966196719681969197019711972197319741975197619771978197919801981198219831984198519861987198819891990199119921993199419951996199719981999200020012002200320042005200620072008200920102011201220132014201520162017201820192020202120222023202420252026202720282029203020312032203320342035203620372038203920402041204220432044204520462047204820492050205120522053205420552056205720582059206020612062206320642065206620672068206920702071207220732074207520762077207820792080208120822083208420852086208720882089209020912092209320942095209620972098209921002101210221032104210521062107210821092110211121122113211421152116211721182119212021212122212321242125212621272128212921302131213221332134213521362137213821392140214121422143214421452146214721482149215021512152215321542155215621572158215921602161216221632164216521662167216821692170217121722173217421752176217721782179218021812182218321842185218621872188218921902191219221932194219521962197219821992200220122022203220422052206220722082209221022112212221322142215221622172218221922202221222222232224222522262227222822292230223122322233223422352236223722382239224022412242224322442245224622472248224922502251225222532254225522562257225822592260226122622263226422652266226722682269227022712272227322742275227622772278227922802281228222832284228522862287228822892290229122922293229422952296229722982299230023012302230323042305230623072308230923102311231223132314231523162317231823192320232123222323232423252326232723282329233023312332233323342335233623372338233923402341234223432344234523462347234823492350235123522353235423552356235723582359236023612362236323642365236623672368236923702371237223732374237523762377237823792380238123822383238423852386238723882389239023912392239323942395239623972398239924002401240224032404240524062407240824092410241124122413241424152416241724182419242024212422242324242425242624272428242924302431243224332434243524362437243824392440244124422443244424452446244724482449245024512452245324542455245624572458245924602461246224632464246524662467246824692470247124722473247424752476247724782479248024812482248324842485248624872488248924902491249224932494249524962497249824992500250125022503250425052506250725082509251025112512251325142515251625172518251925202521252225232524252525262527252825292530253125322533253425352536253725382539254025412542254325442545254625472548254925502551255225532554255525562557255825592560256125622563256425652566256725682569257025712572257325742575257625772578257925802581258225832584258525862587258825892590259125922593259425952596259725982599260026012602260326042605260626072608260926102611261226132614261526162617261826192620262126222623262426252626262726282629263026312632263326342635263626372638263926402641264226432644264526462647264826492650265126522653265426552656265726582659266026612662266326642665266626672668266926702671267226732674267526762677267826792680268126822683268426852686268726882689269026912692269326942695269626972698269927002701270227032704270527062707270827092710271127122713271427152716271727182719272027212722272327242725272627272728272927302731273227332734273527362737273827392740274127422743274427452746274727482749275027512752275327542755275627572758275927602761276227632764276527662767276827692770277127722773277427752776277727782779278027812782278327842785278627872788278927902791279227932794279527962797279827992800280128022803280428052806280728082809281028112812281328142815281628172818281928202821282228232824282528262827282828292830283128322833283428352836283728382839284028412842284328442845284628472848284928502851285228532854285528562857285828592860286128622863286428652866286728682869287028712872287328742875287628772878287928802881288228832884288528862887288828892890289128922893289428952896289728982899290029012902290329042905290629072908290929102911291229132914291529162917291829192920292129222923292429252926292729282929293029312932293329342935293629372938293929402941294229432944294529462947294829492950295129522953295429552956295729582959296029612962296329642965296629672968296929702971297229732974297529762977297829792980298129822983298429852986298729882989299029912992299329942995299629972998299930003001300230033004300530063007300830093010301130123013301430153016301730183019302030213022302330243025302630273028302930303031303230333034303530363037303830393040304130423043304430453046304730483049305030513052305330543055305630573058305930603061306230633064306530663067306830693070307130723073307430753076307730783079308030813082308330843085308630873088308930903091309230933094309530963097309830993100310131023103310431053106310731083109311031113112311331143115311631173118311931203121312231233124312531263127312831293130313131323133313431353136313731383139314031413142314331443145314631473148314931503151315231533154315531563157315831593160316131623163316431653166316731683169317031713172317331743175317631773178317931803181318231833184318531863187318831893190319131923193319431953196319731983199320032013202320332043205320632073208320932103211321232133214321532163217321832193220322132223223322432253226322732283229323032313232323332343235323632373238323932403241324232433244324532463247324832493250325132523253325432553256325732583259326032613262326332643265326632673268326932703271327232733274327532763277327832793280328132823283328432853286328732883289329032913292329332943295329632973298329933003301330233033304330533063307330833093310331133123313331433153316331733183319332033213322332333243325332633273328332933303331333233333334333533363337333833393340334133423343334433453346334733483349335033513352335333543355335633573358335933603361336233633364336533663367336833693370337133723373337433753376337733783379338033813382338333843385338633873388338933903391339233933394339533963397339833993400340134023403340434053406340734083409341034113412341334143415341634173418341934203421342234233424342534263427342834293430343134323433343434353436343734383439344034413442344334443445344634473448344934503451345234533454345534563457345834593460346134623463346434653466346734683469347034713472347334743475347634773478347934803481348234833484348534863487348834893490349134923493349434953496349734983499350035013502350335043505350635073508350935103511351235133514351535163517351835193520352135223523352435253526352735283529353035313532353335343535353635373538353935403541354235433544354535463547354835493550355135523553355435553556355735583559356035613562356335643565356635673568356935703571357235733574357535763577357835793580358135823583358435853586358735883589359035913592359335943595359635973598359936003601360236033604360536063607360836093610361136123613361436153616361736183619362036213622362336243625362636273628362936303631363236333634363536363637363836393640364136423643364436453646364736483649365036513652365336543655365636573658365936603661366236633664366536663667366836693670367136723673367436753676367736783679368036813682368336843685368636873688368936903691369236933694369536963697369836993700370137023703370437053706370737083709371037113712371337143715
  1. #include "lidar_fusion_node.h"
  2. #include "time_sync.h"
  3. #include "lidarheart.h" // 读取雷达状态
  4. #include <ros/ros.h>
  5. #include <pcl_conversions/pcl_conversions.h>
  6. #include <iostream>
  7. #include <iomanip>
  8. #include <fstream>
  9. #include <thread>
  10. #include <functional>
  11. #include <chrono>
  12. #include <map>
  13. #include <limits>
  14. #include <params.h>
  15. #include <atomic>
  16. #include <std_msgs/Empty.h>
  17. #include <cmath>
  18. #include <cstdint>
  19. // 可视化预测圆柱
  20. #include "visualization.h"
  21. // 记录最近一次有效拟合的时间戳与延迟
  22. namespace
  23. {
  24. std::atomic<double> s_last_c1_stamp_sec{0.0};
  25. std::atomic<double> s_last_c1_delay_sec{0.0};
  26. std::atomic<double> s_last_c2_stamp_sec{0.0};
  27. std::atomic<double> s_last_c2_delay_sec{0.0};
  28. }
  29. LidarFusionNode::LidarFusionNode(ros::NodeHandle &pnh, bool wait_for_master, double master_timeout_sec) : pnh_(pnh),
  30. c1_thread_running_(true),
  31. c2_thread_running_(true),
  32. c1_thread_pool_(4),
  33. c2_thread_pool_(4),
  34. c1_fit_pool_(2),
  35. c2_fit_pool_(2),
  36. c1_fitter(loadLidarFusionParams(pnh)),
  37. c2_fitter(loadLidarFusionParams(pnh)),
  38. c1_start_time_(0),
  39. c2_start_time_(0)
  40. {
  41. // 首次加载全部参数
  42. params_ = loadLidarFusionParams(pnh_);
  43. // 构建两组雷达的预测器
  44. c1_predictor_ = std::make_unique<PosePredictor>();
  45. c2_predictor_ = std::make_unique<PosePredictor>();
  46. if (params_.kf_init_center_speed.size() == 3)
  47. {
  48. Eigen::Vector3d v0(params_.kf_init_center_speed[0], params_.kf_init_center_speed[1], params_.kf_init_center_speed[2]);
  49. c1_predictor_->setInitCenterVelocity(v0);
  50. c2_predictor_->setInitCenterVelocity(v0);
  51. }
  52. c1_predictor_->setAccelThreshold(params_.accel_threshold_mps2);
  53. c1_predictor_->setSpeedThreshold(params_.speed_threshold_mps);
  54. c1_predictor_->setForceUpdateInterval(params_.force_update_interval_s);
  55. c2_predictor_->setAccelThreshold(params_.accel_threshold_mps2);
  56. c2_predictor_->setSpeedThreshold(params_.speed_threshold_mps);
  57. c2_predictor_->setForceUpdateInterval(params_.force_update_interval_s);
  58. // 区分 C1 / C2 拟合器来源,后续可用于选择不同可视化话题
  59. c1_fitter.setSourceId(1);
  60. c2_fitter.setSourceId(2);
  61. wait_for_master_ = wait_for_master;
  62. master_timeout_sec_ = master_timeout_sec;
  63. if (wait_for_master_)
  64. {
  65. waitForMaster(master_timeout_sec_);
  66. }
  67. std::vector<double> C1T2_to_1_vec, C1T3_to_1_vec, C1T4_to_1_vec, C1T1_to_S_vec, C1S_to_Ship_vec;
  68. std::vector<double> C2T2_to_1_vec, C2T3_to_1_vec, C2T4_to_1_vec, C2T1_to_S_vec, C2S_to_Ship_vec;
  69. auto params = params_; // 使用缓存的参数
  70. C1T2_to_1_vec = params.C1T2_to_1_vec; // 加载单机1外参
  71. C1T3_to_1_vec = params.C1T3_to_1_vec;
  72. C1T4_to_1_vec = params.C1T4_to_1_vec;
  73. C1T1_to_S_vec = params.C1T1_to_S_vec;
  74. C1S_to_Ship_vec = params.C1S_to_Ship_vec;
  75. C2T2_to_1_vec = params.C2T2_to_1_vec; // 加载单机2外参
  76. C2T3_to_1_vec = params.C2T3_to_1_vec;
  77. C2T4_to_1_vec = params.C2T4_to_1_vec;
  78. C2T1_to_S_vec = params.C2T1_to_S_vec;
  79. C2S_to_Ship_vec = params.C2S_to_Ship_vec;
  80. Comb1lidar1 = params.Comb1lidar1; // 加载话题名称
  81. Comb1lidar2 = params.Comb1lidar2;
  82. Comb1lidar3 = params.Comb1lidar3;
  83. Comb1lidar4 = params.Comb1lidar4;
  84. Comb1cloud = params.Comb1cloud;
  85. Comb2lidar1 = params.Comb2lidar1;
  86. Comb2lidar2 = params.Comb2lidar2;
  87. Comb2lidar3 = params.Comb2lidar3;
  88. Comb2lidar4 = params.Comb2lidar4;
  89. Comb2cloud = params.Comb2cloud;
  90. std::vector<float> roi1 = params.roi1; // C1 第1块 ROI
  91. std::vector<float> roi1_b = params.roi1_b; // C1 第2块 ROI
  92. std::vector<float> roi2 = params.roi2; // C2 第1块 ROI
  93. std::vector<float> roi2_b = params.roi2_b; // C2 第2块 ROI
  94. pixel_size = params.pixel_size; // 加载预处理部分横向滤波纵向滤波的像素大小
  95. // 缓存过滤阈值参数
  96. heightmap_min_diff_ = params.heightmap_min_diff;
  97. widthmap_max_diff_ = params.widthmap_max_diff;
  98. morph_min_contour_points_ = params.morph_min_contour_points;
  99. morph_ratio_min_ = params.morph_ratio_min;
  100. morph_ratio_max_ = params.morph_ratio_max;
  101. rope_filter_linearity_thresh_ = params_.rope_filter_linearity_thresh;
  102. rocket_extract_voxel_ratio_ = params_.rocket_extract_voxel_ratio;
  103. rocket_cluster_threshold_ = params_.rocket_cluster_threshold;
  104. rocket_cluster_min_size_ = params_.rocket_cluster_min_size;
  105. rope_filter_roi_.z_min = static_cast<float>(params_.rope_filter_roi.z_min);
  106. rope_filter_roi_.z_max = static_cast<float>(params_.rope_filter_roi.z_max);
  107. rope_filter_roi_.x_min = static_cast<float>(params_.rope_filter_roi.x_min);
  108. rope_filter_roi_.x_max = static_cast<float>(params_.rope_filter_roi.x_max);
  109. rope_filter_roi_.y_min = static_cast<float>(params_.rope_filter_roi.y_min);
  110. rope_filter_roi_.y_max = static_cast<float>(params_.rope_filter_roi.y_max);
  111. // 组合两块 ROI:前 6 个为 roi_filter1,后 6 个为 roi_filter1_b
  112. if (roi1.size() == 6 && roi1_b.size() == 6)
  113. {
  114. std::copy(roi1.begin(), roi1.end(), roi_1.begin()); // [0..5]
  115. std::copy(roi1_b.begin(), roi1_b.end(), roi_1.begin() + 6); // [6..11]
  116. }
  117. if (roi2.size() == 6 && roi2_b.size() == 6)
  118. {
  119. std::copy(roi2.begin(), roi2.end(), roi_2.begin()); // [0..5]
  120. std::copy(roi2_b.begin(), roi2_b.end(), roi_2.begin() + 6); // [6..11]
  121. }
  122. C1T2_to_1f_ = vecToAffine3f(C1T2_to_1_vec); // 将单机1外参向量转换为仿射矩阵
  123. C1T3_to_1f_ = vecToAffine3f(C1T3_to_1_vec);
  124. C1T4_to_1f_ = vecToAffine3f(C1T4_to_1_vec);
  125. C1T1_to_Sf_ = vecToAffine3f(C1T1_to_S_vec);
  126. C1Sf_to_Shipf_ = vecToAffine3f(C1S_to_Ship_vec);
  127. C2T2_to_1f_ = vecToAffine3f(C2T2_to_1_vec);
  128. C2T3_to_1f_ = vecToAffine3f(C2T3_to_1_vec);
  129. C2T4_to_1f_ = vecToAffine3f(C2T4_to_1_vec);
  130. C2T1_to_Sf_ = vecToAffine3f(C2T1_to_S_vec);
  131. C2Sf_to_Shipf_ = vecToAffine3f(C2S_to_Ship_vec);
  132. C1T1_to_Shipf_ = mergeTransforms(Eigen::Affine3f::Identity(), C1T1_to_Sf_, C1Sf_to_Shipf_); // 单机1雷达1到船体
  133. C1T2_to_Shipf_ = mergeTransforms(C1T2_to_1f_, C1T1_to_Sf_, C1Sf_to_Shipf_); // 单机1雷达2到船体
  134. C1T3_to_Shipf_ = mergeTransforms(C1T3_to_1f_, C1T1_to_Sf_, C1Sf_to_Shipf_); // 单机1雷达3到船体
  135. C1T4_to_Shipf_ = mergeTransforms(C1T4_to_1f_, C1T1_to_Sf_, C1Sf_to_Shipf_); // 单机1雷达4到船体
  136. C2T1_to_Shipf_ = mergeTransforms(Eigen::Affine3f::Identity(), C2T1_to_Sf_, C2Sf_to_Shipf_); // 单机2雷达1到船体
  137. C2T2_to_Shipf_ = mergeTransforms(C2T2_to_1f_, C2T1_to_Sf_, C2Sf_to_Shipf_); // 单机2雷达2到船体
  138. C2T3_to_Shipf_ = mergeTransforms(C2T3_to_1f_, C2T1_to_Sf_, C2Sf_to_Shipf_); // 单机2雷达3到船体
  139. C2T4_to_Shipf_ = mergeTransforms(C2T4_to_1f_, C2T1_to_Sf_, C2Sf_to_Shipf_); // 单机2雷达4到船体
  140. // 盲区平面转换到 ship 坐标系(仅使用 lidar1_to_shell 与 shell_to_ship,顺序为先 lidar1_to_shell 后 shell_to_ship)
  141. auto vec4_to_f = [](const std::vector<double> &v) -> Eigen::Vector4f
  142. {
  143. if (v.size() != 4)
  144. return Eigen::Vector4f::Zero();
  145. return Eigen::Vector4f(static_cast<float>(v[0]), static_cast<float>(v[1]), static_cast<float>(v[2]), static_cast<float>(v[3]));
  146. };
  147. auto transform_plane = [](const Eigen::Matrix4f &H, const Eigen::Vector4f &pi) -> Eigen::Vector4f
  148. {
  149. Eigen::Matrix4f HinvT = H.inverse().transpose();
  150. return HinvT * pi;
  151. };
  152. // C1
  153. {
  154. Eigen::Matrix4f H = (C1Sf_to_Shipf_ * C1T1_to_Sf_).matrix();
  155. c1_blind_planes_ship_[0] = transform_plane(H, vec4_to_f(params_.C1_blind_34_lidar4_plane));
  156. c1_blind_planes_ship_[1] = transform_plane(H, vec4_to_f(params_.C1_blind_34_lidar3_plane));
  157. c1_blind_planes_ship_[2] = transform_plane(H, vec4_to_f(params_.C1_blind_23_lidar3_plane));
  158. c1_blind_planes_ship_[3] = transform_plane(H, vec4_to_f(params_.C1_blind_23_lidar2_plane));
  159. c1_blind_planes_ship_[4] = transform_plane(H, vec4_to_f(params_.C1_blind_1_lidar1_plane));
  160. }
  161. // C2
  162. {
  163. Eigen::Matrix4f H = (C2Sf_to_Shipf_ * C2T1_to_Sf_).matrix();
  164. c2_blind_planes_ship_[0] = transform_plane(H, vec4_to_f(params_.C2_blind_34_lidar4_plane));
  165. c2_blind_planes_ship_[1] = transform_plane(H, vec4_to_f(params_.C2_blind_34_lidar3_plane));
  166. c2_blind_planes_ship_[2] = transform_plane(H, vec4_to_f(params_.C2_blind_23_lidar3_plane));
  167. c2_blind_planes_ship_[3] = transform_plane(H, vec4_to_f(params_.C2_blind_23_lidar2_plane));
  168. c2_blind_planes_ship_[4] = transform_plane(H, vec4_to_f(params_.C2_blind_1_lidar1_plane));
  169. }
  170. // 订阅雷达点云话题
  171. c1_sub1_ = pnh_.subscribe(Comb1lidar1, 10, &LidarFusionNode::c1_cb1, this, ros::TransportHints().tcpNoDelay());
  172. c1_sub2_ = pnh_.subscribe(Comb1lidar2, 10, &LidarFusionNode::c1_cb2, this, ros::TransportHints().tcpNoDelay());
  173. c1_sub3_ = pnh_.subscribe(Comb1lidar3, 10, &LidarFusionNode::c1_cb3, this, ros::TransportHints().tcpNoDelay());
  174. c1_sub4_ = pnh_.subscribe(Comb1lidar4, 10, &LidarFusionNode::c1_cb4, this, ros::TransportHints().tcpNoDelay());
  175. c2_sub1_ = pnh_.subscribe(Comb2lidar1, 10, &LidarFusionNode::c2_cb1, this, ros::TransportHints().tcpNoDelay());
  176. c2_sub2_ = pnh_.subscribe(Comb2lidar2, 10, &LidarFusionNode::c2_cb2, this, ros::TransportHints().tcpNoDelay());
  177. c2_sub3_ = pnh_.subscribe(Comb2lidar3, 10, &LidarFusionNode::c2_cb3, this, ros::TransportHints().tcpNoDelay());
  178. c2_sub4_ = pnh_.subscribe(Comb2lidar4, 10, &LidarFusionNode::c2_cb4, this, ros::TransportHints().tcpNoDelay());
  179. c1_pub_ = pnh_.advertise<sensor_msgs::PointCloud2>(Comb1cloud, 10);
  180. c2_pub_ = pnh_.advertise<sensor_msgs::PointCloud2>(Comb2cloud, 10);
  181. // ===== 注意:先读取参数再启动依赖这些参数的线程,避免线程读取到默认值 =====
  182. // (之前 softsync 线程在参数赋值之前启动,导致 c1_sync_wait_param_ / c2_sync_wait_param_ 仍是默认值)
  183. pnh_.param<int>("/common/simulation", simu, 0);
  184. pnh_.param<int>("/common/delay_ms", delay_JT_ms, 77);
  185. pnh_.param<string>("/common/canid", canid, "0x513");
  186. pnh_.param<string>("/common/sim_path", filename, "1.csv");
  187. pnh_.param<string>("/common/log_path", logpath, "/home/log");
  188. pnh_.param<string>("/common/serverip", sIP, "0xC0A8A0B6");
  189. pnh_.param<int>("/common/serverport", sPORT, 10188);
  190. pnh_.param<string>("/common/clientip", cIP, "0xC0A89791");
  191. pnh_.param<int>("/common/clientport", cPORT, 10188);
  192. pnh_.param<string>("/common/serverip_bak", sIP_bak, "0xC0A8A0B7");
  193. pnh_.param<int>("/common/serverport_bak", sPORT_bak, 10188);
  194. pnh_.param<string>("/common/clientip_bak", cIP_bak, "0xC0A89792");
  195. pnh_.param<int>("/common/clientport_bak", cPORT_bak, 10188);
  196. pnh_.param<double>("/coordinate/SheXiang", SheXiang_para, 0.0);
  197. pnh_.param<double>("/coordinate/Lever1", Lever_para[0], 0.0);
  198. pnh_.param<double>("/coordinate/Lever2", Lever_para[1], 0.0);
  199. pnh_.param<double>("/coordinate/Lever3", Lever_para[2], 0.0);
  200. pnh_.param<double>("/coordinate/JT1", JT_para[0], 0.0);
  201. pnh_.param<double>("/coordinate/JT2", JT_para[1], 0.0);
  202. pnh_.param<double>("/coordinate/JT3", JT_para[2], 0.0);
  203. pnh_.param<double>("/coordinate/GZatt1", GZ_para[0], 0.0);
  204. pnh_.param<double>("/coordinate/GZatt2", GZ_para[1], 0.0);
  205. pnh_.param<double>("/coordinate/GZatt3", GZ_para[2], 0.0);
  206. printf("%s", canid.c_str());
  207. can_main.setValue_id(std::stoi(canid, nullptr, 16));
  208. can_hpyo.setValue_id(std::stoi(canid, nullptr, 16));
  209. can_main.setValue_can(0);
  210. can_hpyo.setValue_can(1);
  211. can_main.set_path(logpath);
  212. can_hpyo.set_path(logpath);
  213. // can_main.setValue_mode(simu);
  214. // can_hpyo.setValue_mode(simu);
  215. // can_main.setValue_filepath(filename);
  216. // can_hpyo.setValue_filepath(filename);
  217. if (!readCsvFile(filename, csv_data_list))
  218. {
  219. ROS_ERROR("read CSV failed");
  220. }
  221. else
  222. {
  223. ROS_INFO("read file %s success", filename.c_str());
  224. }
  225. print_count = csv_data_list.size();
  226. logger.set_path(logpath);
  227. logger.start();
  228. can_main.start();
  229. can_hpyo.start();
  230. // logger.start();
  231. udp_client.set_path(logpath);
  232. udp_client.InitUDP(std::stoul(sIP, nullptr, 16), (unsigned int)sPORT, std::stoul(cIP, nullptr, 16), (unsigned int)cPORT);
  233. udp_client_bak.set_path(logpath);
  234. udp_client_bak.InitUDP(std::stoul(sIP_bak, nullptr, 16), (unsigned int)sPORT_bak, std::stoul(cIP_bak, nullptr, 16), (unsigned int)cPORT_bak);
  235. c1_sync_wait_param_ = params.c1_sync_wait_sec;
  236. c2_sync_wait_param_ = params.c2_sync_wait_sec;
  237. c1_SYNC_WAIT_ = ros::Duration(c1_sync_wait_param_);
  238. c2_SYNC_WAIT_ = ros::Duration(c2_sync_wait_param_);
  239. last_stat_time_ = ros::Time::now();
  240. // 决策等待时间参数
  241. decision_wait_sec_ = params.decision_wait_sec;
  242. // 启动结果对策线程
  243. // 线程启动顺序:确保 softsync 线程最后启动,这样其构造的 Inputs 能拿到更新后的 *_sync_wait_param_
  244. c1_merge_thread_ = std::thread(&LidarFusionNode::c1_mergeThreadLoop, this);
  245. c2_merge_thread_ = std::thread(&LidarFusionNode::c2_mergeThreadLoop, this);
  246. c1_sync_thread_ = std::thread(&LidarFusionNode::c1_doSyncWork, this);
  247. c2_sync_thread_ = std::thread(&LidarFusionNode::c2_doSyncWork, this);
  248. c1_softsync_thread_ = std::thread(&LidarFusionNode::c1_handleSoftSync, this);
  249. c2_softsync_thread_ = std::thread(&LidarFusionNode::c2_handleSoftSync, this);
  250. decision_thread_ = std::thread(&LidarFusionNode::decisionThreadLoop, this);
  251. double hb_timeout = params.lidar_heartbeat_timeout;
  252. int hb_mode = params.lidar_heartbeat_mode; // 0: bit=异常 1: bit=正常
  253. try
  254. {
  255. LidarHeart::setTimeout(hb_timeout);
  256. LidarHeart::setMode(hb_mode);
  257. ROS_INFO_STREAM("LidarHeart initialized: timeout=" << hb_timeout << "s mode=" << (hb_mode == 0 ? "bit=abnormal" : "bit=normal"));
  258. }
  259. catch (const std::exception &e)
  260. {
  261. ROS_ERROR_STREAM("Failed to initialize LidarHeart: " << e.what());
  262. }
  263. // 订阅运行期参数刷新命令
  264. reload_params_sub_ = pnh_.subscribe<std_msgs::Empty>("/reload_lidar_params", 1,
  265. &LidarFusionNode::reloadParamsCallback, this);
  266. }
  267. // 分割字符串函数
  268. std::vector<std::string> LidarFusionNode::split(const std::string &s, char delimiter)
  269. {
  270. std::vector<std::string> tokens;
  271. std::string token;
  272. std::istringstream tokenStream(s);
  273. while (std::getline(tokenStream, token, delimiter))
  274. {
  275. tokens.push_back(token);
  276. }
  277. return tokens;
  278. }
  279. // 从CSV文件读取数据
  280. bool LidarFusionNode::readCsvFile(const std::string &file_path, std::vector<CsvData> &data_list)
  281. {
  282. std::ifstream file(file_path);
  283. if (!file.is_open())
  284. {
  285. ROS_ERROR("can not open CSV file: %s", file_path.c_str());
  286. return false;
  287. }
  288. std::string line;
  289. // 跳过表头
  290. if (std::getline(file, line))
  291. {
  292. ROS_INFO("ignore first line");
  293. }
  294. // 读取每一行数据
  295. while (std::getline(file, line))
  296. {
  297. std::vector<std::string> tokens = split(line, ',');
  298. // 检查列数是否正确
  299. if (tokens.size() != 21)
  300. {
  301. ROS_WARN("line data error,jump: %s", line.c_str());
  302. continue;
  303. }
  304. try
  305. {
  306. CsvData data;
  307. data.index = std::stoi(tokens[0]);
  308. data.timestamp = std::stod(tokens[1]);
  309. data.x = std::stod(tokens[2]);
  310. data.y = std::stod(tokens[3]);
  311. data.z = std::stod(tokens[4]);
  312. data.a = std::stod(tokens[5]);
  313. data.b = std::stod(tokens[6]);
  314. data.c = std::stod(tokens[7]);
  315. data.yaw = std::stod(tokens[8]);
  316. data.pitch = std::stod(tokens[9]);
  317. data.point_count = std::stoi(tokens[10]);
  318. data.residual_mean = std::stod(tokens[11]);
  319. data.is_cross_plane = (std::stoi(tokens[12]) != 0);
  320. data.delay = std::stod(tokens[13]);
  321. data.is_visible = (std::stoi(tokens[14]) != 0);
  322. data.is_prediction = (std::stoi(tokens[15]) != 0);
  323. data.radar_state = std::stoi(tokens[16]);
  324. data.each_lidarstate = std::stoi(tokens[17]);
  325. data.solve_state = std::stoi(tokens[18]);
  326. data.data_state = std::stoi(tokens[19]);
  327. data_list.push_back(data);
  328. // printCsvData(data);
  329. }
  330. catch (const std::exception &e)
  331. {
  332. ROS_WARN("data error: %s, jump", e.what());
  333. continue;
  334. }
  335. }
  336. file.close();
  337. ROS_INFO("read file success, %zu data", data_list.size());
  338. return true;
  339. }
  340. void LidarFusionNode::reloadParamsCallback(const std_msgs::Empty::ConstPtr &)
  341. {
  342. try
  343. {
  344. ROS_INFO("Reloading LidarFusionParams from parameter server...");
  345. LidarFusionParams new_params = loadLidarFusionParams(pnh_);
  346. params_ = new_params;
  347. // 同步运行期可更新的参数
  348. heightmap_min_diff_ = params_.heightmap_min_diff;
  349. widthmap_max_diff_ = params_.widthmap_max_diff;
  350. morph_min_contour_points_ = params_.morph_min_contour_points;
  351. morph_ratio_min_ = params_.morph_ratio_min;
  352. morph_ratio_max_ = params_.morph_ratio_max;
  353. rope_filter_linearity_thresh_ = params_.rope_filter_linearity_thresh;
  354. rocket_extract_voxel_ratio_ = params_.rocket_extract_voxel_ratio;
  355. rocket_cluster_threshold_ = params_.rocket_cluster_threshold;
  356. rocket_cluster_min_size_ = params_.rocket_cluster_min_size;
  357. rope_filter_roi_.z_min = static_cast<float>(params_.rope_filter_roi.z_min);
  358. rope_filter_roi_.z_max = static_cast<float>(params_.rope_filter_roi.z_max);
  359. rope_filter_roi_.x_min = static_cast<float>(params_.rope_filter_roi.x_min);
  360. rope_filter_roi_.x_max = static_cast<float>(params_.rope_filter_roi.x_max);
  361. rope_filter_roi_.y_min = static_cast<float>(params_.rope_filter_roi.y_min);
  362. rope_filter_roi_.y_max = static_cast<float>(params_.rope_filter_roi.y_max);
  363. // ROI 参数实时更新(两块 ROI 组合成 12 元数组)
  364. if (params_.roi1.size() == 6 && params_.roi1_b.size() == 6)
  365. {
  366. std::copy(params_.roi1.begin(), params_.roi1.end(), roi_1.begin());
  367. std::copy(params_.roi1_b.begin(), params_.roi1_b.end(), roi_1.begin() + 6);
  368. }
  369. if (params_.roi2.size() == 6 && params_.roi2_b.size() == 6)
  370. {
  371. std::copy(params_.roi2.begin(), params_.roi2.end(), roi_2.begin());
  372. std::copy(params_.roi2_b.begin(), params_.roi2_b.end(), roi_2.begin() + 6);
  373. }
  374. c1_sync_wait_param_ = params_.c1_sync_wait_sec;
  375. c2_sync_wait_param_ = params_.c2_sync_wait_sec;
  376. c1_SYNC_WAIT_ = ros::Duration(c1_sync_wait_param_);
  377. c2_SYNC_WAIT_ = ros::Duration(c2_sync_wait_param_);
  378. decision_wait_sec_ = params_.decision_wait_sec;
  379. double hb_timeout = params_.lidar_heartbeat_timeout;
  380. int hb_mode = params_.lidar_heartbeat_mode; // 0: bit=异常 1: bit=正常
  381. LidarHeart::setTimeout(hb_timeout);
  382. LidarHeart::setMode(hb_mode);
  383. // 重新计算盲区平面(ship)
  384. auto vec4_to_f = [](const std::vector<double> &v) -> Eigen::Vector4f
  385. {
  386. if (v.size() != 4)
  387. return Eigen::Vector4f::Zero();
  388. return Eigen::Vector4f(static_cast<float>(v[0]), static_cast<float>(v[1]), static_cast<float>(v[2]), static_cast<float>(v[3]));
  389. };
  390. auto transform_plane = [](const Eigen::Matrix4f &H, const Eigen::Vector4f &pi) -> Eigen::Vector4f
  391. {
  392. Eigen::Matrix4f HinvT = H.inverse().transpose();
  393. return HinvT * pi;
  394. };
  395. {
  396. Eigen::Matrix4f H = (C1Sf_to_Shipf_ * C1T1_to_Sf_).matrix();
  397. c1_blind_planes_ship_[0] = transform_plane(H, vec4_to_f(params_.C1_blind_34_lidar4_plane));
  398. c1_blind_planes_ship_[1] = transform_plane(H, vec4_to_f(params_.C1_blind_34_lidar3_plane));
  399. c1_blind_planes_ship_[2] = transform_plane(H, vec4_to_f(params_.C1_blind_23_lidar3_plane));
  400. c1_blind_planes_ship_[3] = transform_plane(H, vec4_to_f(params_.C1_blind_23_lidar2_plane));
  401. c1_blind_planes_ship_[4] = transform_plane(H, vec4_to_f(params_.C1_blind_1_lidar1_plane));
  402. }
  403. {
  404. Eigen::Matrix4f H = (C2Sf_to_Shipf_ * C2T1_to_Sf_).matrix();
  405. c2_blind_planes_ship_[0] = transform_plane(H, vec4_to_f(params_.C2_blind_34_lidar4_plane));
  406. c2_blind_planes_ship_[1] = transform_plane(H, vec4_to_f(params_.C2_blind_34_lidar3_plane));
  407. c2_blind_planes_ship_[2] = transform_plane(H, vec4_to_f(params_.C2_blind_23_lidar3_plane));
  408. c2_blind_planes_ship_[3] = transform_plane(H, vec4_to_f(params_.C2_blind_23_lidar2_plane));
  409. c2_blind_planes_ship_[4] = transform_plane(H, vec4_to_f(params_.C2_blind_1_lidar1_plane));
  410. }
  411. ROS_INFO("LidarFusionParams reloaded successfully.");
  412. }
  413. catch (const std::exception &e)
  414. {
  415. ROS_ERROR("Failed to reload LidarFusionParams: %s", e.what());
  416. }
  417. }
  418. LidarFusionNode::~LidarFusionNode()
  419. {
  420. can_main.stop();
  421. can_hpyo.stop();
  422. logger.stop();
  423. shutting_down_.store(true, std::memory_order_relaxed);
  424. fitting_enabled_.store(false, std::memory_order_relaxed);
  425. // 关闭决策线程
  426. decision_running_.store(false, std::memory_order_relaxed);
  427. {
  428. std::lock_guard<std::mutex> lk(decision_any_mutex_);
  429. }
  430. decision_any_cv_.notify_all();
  431. c1_thread_pool_.stopAccepting();
  432. c2_thread_pool_.stopAccepting();
  433. c1_fit_pool_.stopAccepting();
  434. c2_fit_pool_.stopAccepting();
  435. c1_fit_pool_.discardPending();
  436. c2_fit_pool_.discardPending();
  437. if (c1_syncTimer_.isValid())
  438. c1_syncTimer_.stop();
  439. if (c2_syncTimer_.isValid())
  440. c2_syncTimer_.stop();
  441. c1_thread_running_.store(false, std::memory_order_relaxed);
  442. c2_thread_running_.store(false, std::memory_order_relaxed);
  443. c1_sync_thread_running_.store(false, std::memory_order_relaxed);
  444. c2_sync_thread_running_.store(false, std::memory_order_relaxed);
  445. c1_softsync_running_.store(false, std::memory_order_relaxed);
  446. c2_softsync_running_.store(false, std::memory_order_relaxed);
  447. {
  448. std::lock_guard<std::mutex> lk(c1_cv_mutex_);
  449. c1_cv_.notify_all();
  450. }
  451. {
  452. std::lock_guard<std::mutex> lk(c2_cv_mutex_);
  453. c2_cv_.notify_all();
  454. }
  455. if (decision_thread_.joinable())
  456. decision_thread_.join();
  457. if (c1_merge_thread_.joinable())
  458. c1_merge_thread_.join();
  459. if (c2_merge_thread_.joinable())
  460. c2_merge_thread_.join();
  461. if (c1_sync_thread_.joinable())
  462. c1_sync_thread_.join();
  463. if (c2_sync_thread_.joinable())
  464. c2_sync_thread_.join();
  465. if (c1_softsync_thread_.joinable())
  466. c1_softsync_thread_.join();
  467. if (c2_softsync_thread_.joinable())
  468. c2_softsync_thread_.join();
  469. c1_thread_pool_.discardPending();
  470. c2_thread_pool_.discardPending();
  471. c1_thread_pool_.shutdownNow();
  472. c2_thread_pool_.shutdownNow();
  473. c1_fit_pool_.shutdownNow();
  474. c2_fit_pool_.shutdownNow();
  475. {
  476. std::lock_guard<std::mutex> lg(c1_pending_mutex_);
  477. while (!c1_pending_clouds_.empty())
  478. c1_pending_clouds_.pop();
  479. }
  480. {
  481. std::lock_guard<std::mutex> lg(c2_pending_mutex_);
  482. while (!c2_pending_clouds_.empty())
  483. c2_pending_clouds_.pop();
  484. }
  485. {
  486. std::lock_guard<std::mutex> lg(c1_pose_mutex_);
  487. while (!c1_pose_queue_.empty())
  488. c1_pose_queue_.pop();
  489. }
  490. {
  491. std::lock_guard<std::mutex> lg(c2_pose_mutex_);
  492. while (!c2_pose_queue_.empty())
  493. c2_pose_queue_.pop();
  494. }
  495. }
  496. Eigen::Affine3f LidarFusionNode::vecToAffine3f(const std::vector<double> &vec)
  497. {
  498. Eigen::Matrix4d mat_d;
  499. for (int i = 0; i < 4; ++i)
  500. {
  501. for (int j = 0; j < 4; ++j)
  502. {
  503. mat_d(i, j) = vec[i * 4 + j];
  504. }
  505. }
  506. Eigen::Matrix4f mat_f = mat_d.cast<float>();
  507. return Eigen::Affine3f(mat_f);
  508. }
  509. // 从frame_id中提取需要计算延迟的起始时间,frame_id格式为:"<orig_frame>|<time>"
  510. double LidarFusionNode::extractFirstPointTime(const sensor_msgs::PointCloud2ConstPtr &msg)
  511. {
  512. const std::string &frame_id = msg->header.frame_id;
  513. // 情况1:frame_id 仅为 "map"(或以斜杠开头的 "/map"),时间戳直接取 header.stamp
  514. if (frame_id == "map" || frame_id == "/map")
  515. {
  516. return ros::Time::now().toSec();
  517. }
  518. // 情况2:frame_id 形如 "<orig_frame>|<first_point_time>"
  519. size_t pos = frame_id.find('|');
  520. if (pos != std::string::npos && pos + 1 < frame_id.length())
  521. {
  522. std::string time_str = frame_id.substr(pos + 1);
  523. try
  524. {
  525. double result = std::stod(time_str);
  526. return result;
  527. }
  528. catch (const std::exception &e)
  529. {
  530. ROS_WARN_THROTTLE(5.0, "Failed to parse first_point_time from frame_id: %s", e.what());
  531. }
  532. }
  533. // 无法解析则回退使用 header.stamp
  534. double stamp_sec = msg->header.stamp.toSec();
  535. return stamp_sec > 0 ? stamp_sec : 0;
  536. }
  537. // 从frame_id中提取原始frame_id,去除时间信息
  538. std::string LidarFusionNode::getOriginalFrameId(const std::string &encoded_frame_id)
  539. {
  540. size_t pos = encoded_frame_id.find('|');
  541. if (pos != std::string::npos)
  542. {
  543. return encoded_frame_id.substr(0, pos);
  544. }
  545. return encoded_frame_id;
  546. }
  547. // c1_cb1 - c1_cb4: 单机1四个雷达的回调函数
  548. void LidarFusionNode::c1_cb1(const sensor_msgs::PointCloud2ConstPtr &msg)
  549. {
  550. if (shutting_down_.load(std::memory_order_relaxed))
  551. return;
  552. {
  553. std::lock_guard<std::mutex> lg(c1_in_mutexes_[0]);
  554. c1_in_queues_[0].push(msg);
  555. // printf("%s %f \n", "c1_cb1 = ", msg->header.stamp.toSec());
  556. // printf("%s %f \n", "rosTime1() = ", ros::Time::now().toSec());
  557. }
  558. c1_cv_.notify_one();
  559. }
  560. void LidarFusionNode::c1_cb2(const sensor_msgs::PointCloud2ConstPtr &msg)
  561. {
  562. if (shutting_down_.load(std::memory_order_relaxed))
  563. return;
  564. {
  565. std::lock_guard<std::mutex> lg(c1_in_mutexes_[1]);
  566. c1_in_queues_[1].push(msg);
  567. // printf("%s %f \n", "stamp2 = ", msg->header.stamp.toSec());
  568. // printf("%s %f \n", "rosTime2() = ", ros::Time::now().toSec());
  569. }
  570. c1_cv_.notify_one();
  571. }
  572. void LidarFusionNode::c1_cb3(const sensor_msgs::PointCloud2ConstPtr &msg)
  573. {
  574. if (shutting_down_.load(std::memory_order_relaxed))
  575. return;
  576. {
  577. std::lock_guard<std::mutex> lg(c1_in_mutexes_[2]);
  578. c1_in_queues_[2].push(msg);
  579. // printf("%s %f \n", "stamp3 = ", msg->header.stamp.toSec());
  580. // printf("%s %f \n", "rosTime3() = ", ros::Time::now().toSec());
  581. }
  582. c1_cv_.notify_one();
  583. }
  584. void LidarFusionNode::c1_cb4(const sensor_msgs::PointCloud2ConstPtr &msg)
  585. {
  586. if (shutting_down_.load(std::memory_order_relaxed))
  587. return;
  588. {
  589. std::lock_guard<std::mutex> lg(c1_in_mutexes_[3]);
  590. c1_in_queues_[3].push(msg);
  591. // printf("%s %f \n", "stamp4 = ", msg->header.stamp.toSec());
  592. // printf("%s %f \n", "rosTime4() = ", ros::Time::now().toSec());
  593. }
  594. c1_cv_.notify_one();
  595. }
  596. void LidarFusionNode::c2_cb1(const sensor_msgs::PointCloud2ConstPtr &msg)
  597. {
  598. if (shutting_down_.load(std::memory_order_relaxed))
  599. return;
  600. {
  601. std::lock_guard<std::mutex> lg(c2_in_mutexes_[0]);
  602. c2_in_queues_[0].push(msg);
  603. }
  604. c2_cv_.notify_one();
  605. }
  606. void LidarFusionNode::c2_cb2(const sensor_msgs::PointCloud2ConstPtr &msg)
  607. {
  608. if (shutting_down_.load(std::memory_order_relaxed))
  609. return;
  610. {
  611. std::lock_guard<std::mutex> lg(c2_in_mutexes_[1]);
  612. c2_in_queues_[1].push(msg);
  613. }
  614. c2_cv_.notify_one();
  615. }
  616. void LidarFusionNode::c2_cb3(const sensor_msgs::PointCloud2ConstPtr &msg)
  617. {
  618. if (shutting_down_.load(std::memory_order_relaxed))
  619. return;
  620. {
  621. std::lock_guard<std::mutex> lg(c2_in_mutexes_[2]);
  622. c2_in_queues_[2].push(msg);
  623. }
  624. c2_cv_.notify_one();
  625. }
  626. void LidarFusionNode::c2_cb4(const sensor_msgs::PointCloud2ConstPtr &msg)
  627. {
  628. if (shutting_down_.load(std::memory_order_relaxed))
  629. return;
  630. {
  631. std::lock_guard<std::mutex> lg(c2_in_mutexes_[3]);
  632. c2_in_queues_[3].push(msg);
  633. }
  634. c2_cv_.notify_one();
  635. }
  636. // 软同步处理函数:处理逻辑为:从各个雷达的输入队列中取出点云数据,进行时间软同步,并将同步后的数据批次推入同步队列中,供后续处理使用。
  637. void LidarFusionNode::c1_handleSoftSync()
  638. {
  639. time_sync::Inputs in{
  640. &c1_in_queues_,
  641. &c1_in_mutexes_,
  642. &c1_cv_mutex_,
  643. &c1_cv_,
  644. &c1_softsync_running_,
  645. c1_sync_wait_param_};
  646. // 使用 each_mask 的低 4 位(0=正常,1=异常)选择参与同步的雷达通道
  647. in.get_active = []()
  648. {
  649. std::array<bool, 4> act{true, true, true, true};
  650. try
  651. {
  652. uint8_t each_mask = 0;
  653. int overall = 0;
  654. LidarHeart::getStatus(each_mask, overall);
  655. for (int i = 0; i < 4; ++i)
  656. {
  657. bool abnormal = ((each_mask >> i) & 0x1) != 0; // 1=异常
  658. act[i] = !abnormal; // 仅正常通道参与
  659. }
  660. }
  661. catch (...)
  662. {
  663. // 失败则默认全部参与
  664. }
  665. // act = {false,true,true,true};
  666. return act;
  667. };
  668. auto push_fn = [this](const std::vector<int> &ids,
  669. const std::vector<sensor_msgs::PointCloud2ConstPtr> &msgs)
  670. {
  671. std::lock_guard<std::mutex> qlg(c1_sync_queue_mutex_);
  672. c1_sync_queue_.push(SyncBatch{ids, msgs});
  673. };
  674. // 实时更新 C1 时间同步状态(0=正常,1=异常)
  675. in.set_time_sync_state = [this](bool ok)
  676. {
  677. c1_time_sync_state_.store(ok ? 0 : 1, std::memory_order_relaxed);
  678. };
  679. time_sync::two_phase_soft_sync(in, push_fn);
  680. }
  681. void LidarFusionNode::c2_handleSoftSync()
  682. {
  683. time_sync::Inputs in{
  684. &c2_in_queues_,
  685. &c2_in_mutexes_,
  686. &c2_cv_mutex_,
  687. &c2_cv_,
  688. &c2_softsync_running_,
  689. c2_sync_wait_param_};
  690. // 使用 each_mask 的高 4 位(bit[4..7],0=正常,1=异常)选择参与同步的雷达通道
  691. in.get_active = []()
  692. {
  693. std::array<bool, 4> act{true, true, true, true};
  694. try
  695. {
  696. uint8_t each_mask = 0;
  697. int overall = 0;
  698. LidarHeart::getStatus(each_mask, overall);
  699. for (int j = 0; j < 4; ++j)
  700. {
  701. bool abnormal = ((each_mask >> (4 + j)) & 0x1) != 0; // 1=异常
  702. act[j] = !abnormal; // 仅正常通道
  703. }
  704. }
  705. catch (...)
  706. {
  707. // 失败则默认全部
  708. }
  709. return act;
  710. };
  711. auto push_fn = [this](const std::vector<int> &ids,
  712. const std::vector<sensor_msgs::PointCloud2ConstPtr> &msgs)
  713. {
  714. std::lock_guard<std::mutex> qlg(c2_sync_queue_mutex_);
  715. c2_sync_queue_.push(SyncBatch{ids, msgs});
  716. };
  717. // 实时更新 C2 时间同步状态(0=正常,1=异常)
  718. in.set_time_sync_state = [this](bool ok)
  719. {
  720. c2_time_sync_state_.store(ok ? 0 : 1, std::memory_order_relaxed);
  721. };
  722. time_sync::two_phase_soft_sync(in, push_fn);
  723. }
  724. // 同步批次入队函数:将已到达的点云数据打包成同步批次,推入同步队列中,供后续处理使用。
  725. void LidarFusionNode::c1_enqueueSyncBatch()
  726. {
  727. std::vector<int> ids;
  728. std::vector<sensor_msgs::PointCloud2ConstPtr> clouds;
  729. {
  730. std::lock_guard<std::mutex> lg(c1_mtx_);
  731. for (int i = 0; i < 4; ++i)
  732. {
  733. if (c1_box_[i].arrived)
  734. {
  735. ids.push_back(i);
  736. clouds.push_back(c1_box_[i].cloud);
  737. c1_box_[i].arrived = false;
  738. c1_box_[i].cloud.reset();
  739. }
  740. }
  741. }
  742. if (ids.empty())
  743. return;
  744. {
  745. std::lock_guard<std::mutex> qlg(c1_sync_queue_mutex_);
  746. c1_sync_queue_.push(SyncBatch{ids, clouds});
  747. }
  748. }
  749. // 同步工作处理函数:从同步队列中取出同步批次,使用线程池并行处理每个雷达的点云坐标转换和ROI,处理完成后将结果打包成待处理云数据,推入待处理队列中。
  750. void LidarFusionNode::c1_doSyncWork()
  751. {
  752. while (c1_sync_thread_running_.load(std::memory_order_relaxed) && ros::ok())
  753. {
  754. SyncBatch batch;
  755. bool has = false;
  756. // 从同步队列中取出一个批次
  757. {
  758. std::lock_guard<std::mutex> lg(c1_sync_queue_mutex_);
  759. if (!c1_sync_queue_.empty())
  760. {
  761. batch = c1_sync_queue_.front();
  762. c1_sync_queue_.pop();
  763. has = true;
  764. }
  765. }
  766. if (!has)
  767. {
  768. continue;
  769. }
  770. std::vector<CloudType> processed_clouds(4);
  771. std::vector<std::future<void>> futures;
  772. // 并行处理每个雷达的点云数据
  773. for (size_t idx = 0; idx < batch.lidar_ids.size(); ++idx)
  774. {
  775. int lidar_id = batch.lidar_ids[idx];
  776. auto cloud_ptr = batch.clouds[idx];
  777. futures.emplace_back(c1_thread_pool_.AddTask([this, lidar_id, cloud_ptr, &processed_clouds]()
  778. {
  779. try {
  780. switch (lidar_id) {
  781. case 0:
  782. processed_clouds[lidar_id] = this->c1_funcLidar1(cloud_ptr);//ROI和坐标转换
  783. break;
  784. case 1:
  785. processed_clouds[lidar_id] = this->c1_funcLidar2(cloud_ptr);
  786. break;
  787. case 2:
  788. processed_clouds[lidar_id] = this->c1_funcLidar3(cloud_ptr);
  789. break;
  790. case 3:
  791. processed_clouds[lidar_id] = this->c1_funcLidar4(cloud_ptr);
  792. break;
  793. }
  794. } catch(const std::exception &e) {
  795. ROS_ERROR("C1 Lidar %d task failed: %s", lidar_id, e.what());
  796. } }));
  797. }
  798. for (auto &f : futures)
  799. {
  800. if (!f.valid())
  801. {
  802. continue;
  803. }
  804. try
  805. {
  806. f.wait();
  807. }
  808. catch (const std::exception &e)
  809. {
  810. ROS_ERROR("Wait C1 future failed: %s", e.what());
  811. }
  812. }
  813. PendingCloud data;
  814. data.ready_lidar_ids = batch.lidar_ids;
  815. data.header = batch.clouds[0]->header;
  816. double earliest_time = std::numeric_limits<double>::max();
  817. double lidar_time = std::numeric_limits<double>::max();
  818. // 找到所有点云中时间最早的一个作为当前同步批次的时间戳
  819. for (auto &cloud_ptr : batch.clouds)
  820. {
  821. double t = cloud_ptr->header.stamp.toSec();
  822. if (t > 0 && t < lidar_time)
  823. {
  824. lidar_time = t;
  825. }
  826. }
  827. data.header.stamp = ros::Time(lidar_time);
  828. for (auto &cloud_ptr : batch.clouds)
  829. {
  830. double t = extractFirstPointTime(cloud_ptr);
  831. if (t > 0 && t < earliest_time)
  832. {
  833. earliest_time = t;
  834. }
  835. }
  836. // i = 0;
  837. data.lidar_start_time = (earliest_time != std::numeric_limits<double>::max())
  838. ? earliest_time
  839. : 0;
  840. // // 将该批次的时间戳写入文本文件(追加模式)
  841. // try {
  842. // std::ofstream ts_out("/home/ubuntu/c1_batches_timestamps.txt", std::ios::app);
  843. // if (ts_out.is_open()) {
  844. // // 记录批次的统一时间戳(header.stamp)与首点时间(lidar_start_time)以及批次大小
  845. // ts_out << std::fixed << std::setprecision(9)
  846. // << "batch_begin header_stamp_sec=" << data.header.stamp.toSec() << ", "
  847. // << "lidar_start_time=" << data.lidar_start_time << ", "
  848. // << "batch_size=" << batch.clouds.size() << std::endl;
  849. // // 逐帧记录:每个通道在该批次中的原始 header.stamp 与首点时间
  850. // for (size_t i = 0; i < batch.clouds.size(); ++i) {
  851. // const auto &msg = batch.clouds[i];
  852. // double stamp_sec = msg->header.stamp.toSec();
  853. // double first_point_time = extractFirstPointTime(msg);
  854. // int lidar_id = (i < batch.lidar_ids.size()) ? batch.lidar_ids[i] : -1;
  855. // ts_out << " frame lidar_id=" << lidar_id
  856. // << ", header_stamp_sec=" << stamp_sec
  857. // << ", first_point_time=" << first_point_time
  858. // << ", frame_id=\"" << msg->header.frame_id << "\""
  859. // << std::endl;
  860. // }
  861. // ts_out << "batch_end" << std::endl;
  862. // } else {
  863. // ROS_WARN_THROTTLE(5.0, "Failed to open c1_batches_timestamps.txt for writing");
  864. // }
  865. // } catch (const std::exception &e) {
  866. // ROS_WARN_THROTTLE(5.0, "Write C1 timestamps failed: %s", e.what());
  867. // }
  868. // 将处理后的点云数据存入待处理云数据结构中
  869. for (int id : batch.lidar_ids)
  870. {
  871. data.ready_clouds[id] = processed_clouds[id];
  872. }
  873. {
  874. std::lock_guard<std::mutex> pending_lg(c1_pending_mutex_);
  875. c1_pending_clouds_.push(data);
  876. }
  877. }
  878. }
  879. void LidarFusionNode::c2_enqueueSyncBatch()
  880. {
  881. std::vector<int> ids;
  882. std::vector<sensor_msgs::PointCloud2ConstPtr> clouds;
  883. {
  884. std::lock_guard<std::mutex> lg(c2_mtx_);
  885. for (int i = 0; i < 4; ++i)
  886. {
  887. if (c2_box_[i].arrived)
  888. {
  889. ids.push_back(i);
  890. clouds.push_back(c2_box_[i].cloud);
  891. c2_box_[i].arrived = false;
  892. c2_box_[i].cloud.reset();
  893. }
  894. }
  895. }
  896. if (ids.empty())
  897. return;
  898. {
  899. std::lock_guard<std::mutex> qlg(c2_sync_queue_mutex_);
  900. c2_sync_queue_.push(SyncBatch{ids, clouds});
  901. }
  902. }
  903. void LidarFusionNode::c2_doSyncWork()
  904. {
  905. while (c2_sync_thread_running_.load(std::memory_order_relaxed) && ros::ok())
  906. {
  907. SyncBatch batch;
  908. bool has = false;
  909. {
  910. std::lock_guard<std::mutex> lg(c2_sync_queue_mutex_);
  911. if (!c2_sync_queue_.empty())
  912. {
  913. batch = c2_sync_queue_.front();
  914. c2_sync_queue_.pop();
  915. has = true;
  916. }
  917. }
  918. if (!has)
  919. {
  920. continue;
  921. }
  922. std::vector<CloudType> processed_clouds(4);
  923. std::vector<std::future<void>> futures;
  924. for (size_t idx = 0; idx < batch.lidar_ids.size(); ++idx)
  925. {
  926. int lidar_id = batch.lidar_ids[idx];
  927. auto cloud_ptr = batch.clouds[idx];
  928. futures.emplace_back(
  929. c2_thread_pool_.AddTask([this, lidar_id, cloud_ptr, &processed_clouds]()
  930. {
  931. try {
  932. switch (lidar_id) {
  933. case 0:
  934. processed_clouds[lidar_id] = this->c2_funcLidar1(cloud_ptr);
  935. break;
  936. case 1:
  937. processed_clouds[lidar_id] = this->c2_funcLidar2(cloud_ptr);
  938. break;
  939. case 2:
  940. processed_clouds[lidar_id] = this->c2_funcLidar3(cloud_ptr);
  941. break;
  942. case 3:
  943. processed_clouds[lidar_id] = this->c2_funcLidar4(cloud_ptr);
  944. break;
  945. }
  946. } catch (const std::exception &e) {
  947. ROS_ERROR("C2 Lidar %d task failed: %s", lidar_id, e.what());
  948. } }));
  949. }
  950. for (auto &f : futures)
  951. {
  952. if (!f.valid())
  953. {
  954. continue;
  955. }
  956. try
  957. {
  958. f.wait();
  959. }
  960. catch (const std::exception &e)
  961. {
  962. ROS_ERROR("Wait C2 future failed: %s", e.what());
  963. }
  964. }
  965. PendingCloud data;
  966. data.ready_lidar_ids = batch.lidar_ids;
  967. data.header = batch.clouds[0]->header;
  968. double earliest_time = std::numeric_limits<double>::max();
  969. double lidar_time = std::numeric_limits<double>::max();
  970. for (auto &cloud_ptr : batch.clouds)
  971. {
  972. double t = cloud_ptr->header.stamp.toSec();
  973. if (t > 0 && t < lidar_time)
  974. {
  975. lidar_time = t;
  976. }
  977. }
  978. data.header.stamp = ros::Time(lidar_time);
  979. for (auto &cloud_ptr : batch.clouds)
  980. {
  981. double t = extractFirstPointTime(cloud_ptr);
  982. if (t > 0 && t < earliest_time)
  983. {
  984. earliest_time = t;
  985. }
  986. }
  987. data.lidar_start_time = (earliest_time != std::numeric_limits<double>::max()) ? earliest_time : 0;
  988. // // 将该批次的时间戳写入文本文件(追加模式)
  989. // try {
  990. // std::ofstream ts_out("/home/ubuntu/c2_batches_timestamps.txt", std::ios::app);
  991. // if (ts_out.is_open()) {
  992. // ts_out << std::fixed << std::setprecision(9)
  993. // << "batch_begin header_stamp_sec=" << data.header.stamp.toSec() << ", "
  994. // << "lidar_start_time=" << data.lidar_start_time << ", "
  995. // << "batch_size=" << batch.clouds.size() << std::endl;
  996. // for (size_t i = 0; i < batch.clouds.size(); ++i) {
  997. // const auto &msg = batch.clouds[i];
  998. // double stamp_sec = msg->header.stamp.toSec();
  999. // double first_point_time = extractFirstPointTime(msg);
  1000. // int lidar_id = (i < batch.lidar_ids.size()) ? batch.lidar_ids[i] : -1;
  1001. // ts_out << " frame lidar_id=" << lidar_id
  1002. // << ", header_stamp_sec=" << stamp_sec
  1003. // << ", first_point_time=" << first_point_time
  1004. // << ", frame_id=\"" << msg->header.frame_id << "\""
  1005. // << std::endl;
  1006. // }
  1007. // ts_out << "batch_end" << std::endl;
  1008. // } else {
  1009. // ROS_WARN_THROTTLE(5.0, "Failed to open c2_batches_timestamps.txt for writing");
  1010. // }
  1011. // } catch (const std::exception &e) {
  1012. // ROS_WARN_THROTTLE(5.0, "Write C2 timestamps failed: %s", e.what());
  1013. // }
  1014. // 将处理后的点云数据存入待处理云数据结构中
  1015. for (int id : batch.lidar_ids)
  1016. {
  1017. data.ready_clouds[id] = processed_clouds[id];
  1018. }
  1019. {
  1020. std::lock_guard<std::mutex> pending_lg(c2_pending_mutex_);
  1021. c2_pending_clouds_.push(data);
  1022. }
  1023. }
  1024. }
  1025. // 决策函数:根据两个PoseData的有效性和拟合残差选择最佳结果
  1026. PoseData LidarFusionNode::decideTwo(const PoseData &m1, const PoseData &m2)
  1027. {
  1028. const bool m1_ok = (m1.valid == 0);
  1029. const bool m2_ok = (m2.valid == 0);
  1030. if (1)
  1031. {
  1032. if (m1_ok && m2_ok)
  1033. {
  1034. // 若两结果均为测量值,则取延迟小的结果作为输出结果
  1035. if (m1.IsMeasure == 1 && m2.IsMeasure == 1)
  1036. {
  1037. return m1;
  1038. }
  1039. else if (m1.IsMeasure == 1 && m2.IsMeasure == 0)
  1040. {
  1041. return m1; // 若m1结果为测量值,则返回m1的结果
  1042. }
  1043. else if (m1.IsMeasure == 0 && m2.IsMeasure == 1)
  1044. {
  1045. return m2; // 若m2结果为测量值,则返回m2的结果
  1046. }
  1047. else if (m1.IsMeasure == 0 && m2.IsMeasure == 0)
  1048. {
  1049. return m1; // 若两结果均为预测值,则取延迟小的结果作为输出结果
  1050. }
  1051. }
  1052. else if (m1_ok)
  1053. {
  1054. return m1;
  1055. }
  1056. else if (m2_ok)
  1057. {
  1058. return m2;
  1059. }
  1060. else
  1061. {
  1062. return m1; // 都无效时保持 m1
  1063. }
  1064. }
  1065. }
  1066. // 决策函数:仅有一个PoseData时,直接返回该结果
  1067. PoseData LidarFusionNode::decideOne(const PoseData &m1)
  1068. {
  1069. return m1;
  1070. }
  1071. // 获取最佳结果函数:从第二个雷达队列中获取数据,并与第一个雷达的数据进行决策,返回最佳结果
  1072. PoseData LidarFusionNode::getBestResult(PoseData &data1)
  1073. {
  1074. bool has_data2 = false;
  1075. PoseData data2, result;
  1076. lidar2_mutex_.lock();
  1077. if (!lidarCombine2.empty())
  1078. {
  1079. while (lidarCombine2.size() > 1)
  1080. lidarCombine2.pop();
  1081. data2 = lidarCombine2.front();
  1082. lidarCombine2.pop();
  1083. has_data2 = true;
  1084. }
  1085. lidar2_mutex_.unlock();
  1086. if (has_data2)
  1087. {
  1088. result = decideTwo(data1, data2);
  1089. }
  1090. else
  1091. {
  1092. result = decideOne(data1);
  1093. }
  1094. return result;
  1095. }
  1096. // 拼接处理线程函数:从待处理云队列中取出数据,进行点云拼接和姿态拟合,并发布结果
  1097. void LidarFusionNode::c1_mergeThreadLoop()
  1098. {
  1099. while (c1_thread_running_.load(std::memory_order_relaxed) && ros::ok())
  1100. {
  1101. PendingCloud data;
  1102. bool has_data = false;
  1103. // 从待处理云队列中取出一个数据
  1104. {
  1105. std::lock_guard<std::mutex> pending_lg(c1_pending_mutex_);
  1106. if (!c1_pending_clouds_.empty())
  1107. {
  1108. data = c1_pending_clouds_.front();
  1109. c1_pending_clouds_.pop();
  1110. has_data = true;
  1111. }
  1112. }
  1113. // 进行点云拼接和姿态拟合
  1114. if (has_data)
  1115. {
  1116. CloudType merged_cloud;
  1117. size_t total_points = 0;
  1118. // 计算总点数以预分配内存
  1119. for (int lidar_id : data.ready_lidar_ids)
  1120. {
  1121. total_points += data.ready_clouds[lidar_id].size();
  1122. }
  1123. merged_cloud.reserve(total_points);
  1124. // 拼接各雷达点云
  1125. for (int lidar_id : data.ready_lidar_ids)
  1126. {
  1127. const auto &cloud = data.ready_clouds[lidar_id];
  1128. merged_cloud.insert(merged_cloud.end(), cloud.begin(), cloud.end());
  1129. }
  1130. double gps_timestamp = data.header.stamp.toNSec() / 1e9;
  1131. bool save_pcd = true;
  1132. if (save_pcd)
  1133. {
  1134. // Save debug cloud when timestamp is within 1 ms of the target
  1135. constexpr double target_ts = 10.100152;
  1136. constexpr double ts_tolerance = 0.001; // seconds (1 ms)
  1137. cout << std::fixed << std::setprecision(6) << "target_ts: " << target_ts << endl;
  1138. cout << std::fixed << std::setprecision(6) << "gps_timestamp: " << gps_timestamp << endl;
  1139. if (std::abs(gps_timestamp - target_ts) <= ts_tolerance)
  1140. {
  1141. std::ostringstream oss;
  1142. oss << "/tmp/processedCloudC1" << std::fixed << std::setprecision(6) << gps_timestamp << ".pcd";
  1143. const std::string pcd_path = oss.str();
  1144. pcl::io::savePCDFileBinary(pcd_path, merged_cloud);
  1145. std::cout << "[CylinderFitter] cp or dir NaN at t=" << std::fixed << std::setprecision(6)
  1146. << gps_timestamp << ", saved cloud: " << pcd_path << std::endl;
  1147. }
  1148. }
  1149. TicToc t1;
  1150. // 提取Rocket点云:rocketExtract 仍使用单块 6 维 ROI,这里取 roi_1 的前 6 个元素
  1151. CloudType rocket_cloud = rocketExtract(
  1152. merged_cloud,
  1153. std::array<float, 6>{roi_1[0], roi_1[1],
  1154. roi_1[2], roi_1[3],
  1155. roi_1[10], roi_1[5]},
  1156. gps_timestamp);
  1157. LOG(INFO) << std::fixed << std::setprecision(6) << "gps_timestamp: " << gps_timestamp << std::endl;
  1158. LOG(INFO) << "C1 rocket rocketExtract: " << t1.toc() << " ms" << std::endl;
  1159. getTempResult1_ = false;
  1160. // 提交异步拟合任务
  1161. if (!shutting_down_.load(std::memory_order_relaxed) && fitting_enabled_.load(std::memory_order_relaxed))
  1162. {
  1163. try
  1164. {
  1165. auto fit_task = [this, rocket_cloud, gps_timestamp, lidar_start = data.lidar_start_time]()
  1166. {
  1167. if (shutting_down_.load(std::memory_order_relaxed) || !fitting_enabled_.load(std::memory_order_relaxed))
  1168. {
  1169. return PoseData();
  1170. }
  1171. ros::Time fit_start = ros::Time::now();
  1172. CloudType::Ptr cloud_ptr(new CloudType(rocket_cloud));
  1173. // double timestamp = lidar_start > 0.0f ? lidar_start : ros::Time::now().toSec();
  1174. TicToc t_fit;
  1175. PoseData pose = c1_fitter.fitCylinder(cloud_ptr, gps_timestamp, &c1_blind_planes_ship_);
  1176. // 同步状态写入结果(0=正常,1=异常)
  1177. LOG(INFO) << "C1 fitCylinder: " << t_fit.toc() << " ms" << std::endl;
  1178. pose.time_sync_state = c1_time_sync_state_.load(std::memory_order_relaxed);
  1179. if (shutting_down_.load(std::memory_order_relaxed))
  1180. {
  1181. return pose;
  1182. }
  1183. ros::Time end_time = ros::Time::now();
  1184. pose.delay_time = lidar_start;
  1185. double detection_time = end_time.toSec() - fit_start.toSec();
  1186. // 更新预测器历史帧
  1187. if (c1_predictor_ && pose.valid == 0 && !pose.bottomCenter.hasNaN() && !pose.bottomCenter.array().isInf().any())
  1188. {
  1189. c1_predictor_->setBlindZoneActive(c1_fitter.isBlindZoneActive());
  1190. Eigen::Vector3f cen = pose.bottomCenter.cast<float>();
  1191. Eigen::Vector3f ax = pose.axis.cast<float>();
  1192. c1_predictor_->updateHistoryAndFilter(pose.timestamp, cen, ax, pose.fitResidual);
  1193. // 记录最近一次时间基准
  1194. s_last_c1_stamp_sec.store(pose.timestamp, std::memory_order_relaxed);
  1195. s_last_c1_delay_sec.store(pose.delay_time, std::memory_order_relaxed);
  1196. posedetect_vis::publishPoint(cen, "posedetect_points", 101, 0.1f, 0.95f, 0.1f, 0.95f, 1.0f);
  1197. }
  1198. decision_any_cv_.notify_all();
  1199. // 记录 C1 拟合结果
  1200. {
  1201. static std::ofstream log_c1_fit("/home/zxy/results/c1_fit_result.log", std::ios::app);
  1202. static bool header_written_c1 = false;
  1203. if (!header_written_c1 && log_c1_fit.is_open())
  1204. {
  1205. log_c1_fit << "timestamp delay_time bottomCenter_x bottomCenter_y bottomCenter_z axis_x axis_y axis_z elevation azimuth fitResidual valid cloudNumber is_predict IsMeasure height_source" << std::endl;
  1206. log_c1_fit.flush();
  1207. header_written_c1 = true;
  1208. }
  1209. if (log_c1_fit.is_open())
  1210. {
  1211. log_c1_fit << std::fixed << std::setprecision(6)
  1212. << pose.timestamp << " "
  1213. << pose.delay_time << " "
  1214. << pose.bottomCenter.x() << " " << pose.bottomCenter.y() << " " << pose.bottomCenter.z() << " "
  1215. << pose.axis.x() << " " << pose.axis.y() << " " << pose.axis.z() << " "
  1216. << pose.elevation_angle << " "
  1217. << pose.azimuth_angle << " "
  1218. << pose.fitResidual << " "
  1219. << (int)pose.valid << " "
  1220. << pose.cloudNumber << " "
  1221. << (int)pose.is_predict << " "
  1222. << (int)pose.IsMeasure << " "
  1223. << pose.bottom_height_source << std::endl;
  1224. log_c1_fit.flush();
  1225. }
  1226. }
  1227. return pose;
  1228. };
  1229. c1_fit_tasks_++;
  1230. c1_fit_pool_.AddTask(std::move(fit_task));
  1231. }
  1232. catch (const std::exception &e)
  1233. {
  1234. ROS_ERROR("c1 async fit task submission failed: %s", e.what());
  1235. }
  1236. }
  1237. // 发布拼接后的点云
  1238. sensor_msgs::PointCloud2 output_msg;
  1239. pcl::toROSMsg(rocket_cloud, output_msg);
  1240. output_msg.header = data.header;
  1241. output_msg.header.frame_id = "map";
  1242. if (ros::ok())
  1243. {
  1244. c1_pub_.publish(output_msg);
  1245. }
  1246. c1_frames_++;
  1247. if ((c1_frames_ % 100 == 0) && ros::Time::now() - last_stat_time_ > ros::Duration(1.0))
  1248. {
  1249. // ROS_INFO_STREAM("[STAT] C1 frames=" << c1_frames_.load() << " fit_tasks=" << c1_fit_tasks_.load());
  1250. last_stat_time_ = ros::Time::now();
  1251. }
  1252. }
  1253. }
  1254. fitting_enabled_.store(false, std::memory_order_relaxed);
  1255. ROS_INFO("拼接线程已正常退出");
  1256. }
  1257. void LidarFusionNode::c2_mergeThreadLoop()
  1258. {
  1259. while (c2_thread_running_.load(std::memory_order_relaxed) && ros::ok())
  1260. {
  1261. PendingCloud data;
  1262. bool has_data = false;
  1263. {
  1264. std::lock_guard<std::mutex> pending_lg(c2_pending_mutex_);
  1265. if (!c2_pending_clouds_.empty())
  1266. {
  1267. data = c2_pending_clouds_.front();
  1268. c2_pending_clouds_.pop();
  1269. has_data = true;
  1270. }
  1271. }
  1272. if (has_data)
  1273. {
  1274. CloudType merged_cloud;
  1275. size_t total_points = 0;
  1276. for (int lidar_id : data.ready_lidar_ids)
  1277. {
  1278. total_points += data.ready_clouds[lidar_id].size();
  1279. }
  1280. merged_cloud.reserve(total_points);
  1281. for (int lidar_id : data.ready_lidar_ids)
  1282. {
  1283. const auto &cloud = data.ready_clouds[lidar_id];
  1284. merged_cloud.insert(merged_cloud.end(), cloud.begin(), cloud.end());
  1285. }
  1286. double gps_timestamp = data.header.stamp.toNSec() / 1e9;
  1287. bool save_pcd = false;
  1288. if (save_pcd)
  1289. {
  1290. // Save debug cloud when timestamp is within 1 ms of the target
  1291. constexpr double target_ts = 5.900152;
  1292. constexpr double ts_tolerance = 0.001; // seconds (1 ms)
  1293. cout << std::fixed << std::setprecision(6) << "target_ts: " << target_ts << endl;
  1294. cout << std::fixed << std::setprecision(6) << "gps_timestamp: " << gps_timestamp << endl;
  1295. if (std::abs(gps_timestamp - target_ts) <= ts_tolerance)
  1296. {
  1297. std::ostringstream oss;
  1298. oss << "/tmp/processedCloudC2" << std::fixed << std::setprecision(6) << gps_timestamp << ".pcd";
  1299. const std::string pcd_path = oss.str();
  1300. pcl::io::savePCDFileBinary(pcd_path, merged_cloud);
  1301. std::cout << "[CylinderFitter] cp or dir NaN at t=" << std::fixed << std::setprecision(6)
  1302. << gps_timestamp << ", saved cloud: " << pcd_path << std::endl;
  1303. }
  1304. }
  1305. // 提取Rocket点云:rocketExtract 仍使用单块 6 维 ROI,这里取 roi_2 的前 6 个元素
  1306. ros::Time extract_start_time = ros::Time::now();
  1307. CloudType rocket_cloud = rocketExtract(
  1308. merged_cloud,
  1309. std::array<float, 6>{roi_2[0], roi_2[1],
  1310. roi_2[2], roi_2[3],
  1311. roi_2[10], roi_2[5]},
  1312. gps_timestamp);
  1313. ros::Time extract_end_time = ros::Time::now();
  1314. const double extract_time_ms = (extract_end_time - extract_start_time).toSec() * 1000.0; // ms
  1315. // ROS_INFO_STREAM("C2 Rocket Extract time: " << std::fixed << std::setprecision(3)
  1316. // << extract_time_ms << " ms");
  1317. if (!shutting_down_.load(std::memory_order_relaxed) && fitting_enabled_.load(std::memory_order_relaxed))
  1318. {
  1319. try
  1320. {
  1321. auto fit_task = [this, rocket_cloud, gps_timestamp, lidar_start = data.lidar_start_time]()
  1322. {
  1323. if (shutting_down_.load(std::memory_order_relaxed) || !fitting_enabled_.load(std::memory_order_relaxed))
  1324. return PoseData();
  1325. CloudType::Ptr cloud_ptr(new CloudType(rocket_cloud));
  1326. // printf("%s %f \n" , "lidar_start = ", lidar_start);
  1327. // printf("%s %d \n" , "cloud_ptr = ", static_cast<double>(cloud_ptr->header.stamp) / 1e9);
  1328. // double timestamp = lidar_start > 0.0f ? lidar_start : ros::Time::now().toSec();
  1329. // std::cout << "gps_timestamp: " << gps_timestamp << std::endl;
  1330. PoseData pose = c2_fitter.fitCylinder(cloud_ptr, gps_timestamp, &c2_blind_planes_ship_);
  1331. // 同步状态写入结果(0=正常,1=异常)
  1332. pose.time_sync_state = c2_time_sync_state_.load(std::memory_order_relaxed);
  1333. if (shutting_down_.load(std::memory_order_relaxed))
  1334. return pose;
  1335. ros::Time end_time = ros::Time::now();
  1336. // if (lidar_start > 0) {
  1337. // pose.delay_time = lidar_start;
  1338. // } else {
  1339. // pose.delay_time = 0;
  1340. // }
  1341. pose.delay_time = lidar_start;
  1342. // 更新预测器历史帧
  1343. if (c2_predictor_ && pose.valid == 0 && !pose.bottomCenter.hasNaN() && !pose.bottomCenter.array().isInf().any())
  1344. {
  1345. c2_predictor_->setBlindZoneActive(c2_fitter.isBlindZoneActive());
  1346. Eigen::Vector3f cen = pose.bottomCenter.cast<float>();
  1347. Eigen::Vector3f ax = pose.axis.cast<float>();
  1348. c2_predictor_->updateHistoryAndFilter(pose.timestamp, cen, ax, pose.fitResidual);
  1349. // 记录最近一次时间基准(C2)
  1350. s_last_c2_stamp_sec.store(pose.timestamp, std::memory_order_relaxed);
  1351. s_last_c2_delay_sec.store(pose.delay_time, std::memory_order_relaxed);
  1352. // Eigen::Vector3f quan_cen(0.0f, 0.0f, 0.0f);
  1353. posedetect_vis::publishPoint(cen, "posedetect_points", 102, 0.1f, 0.95f, 0.1f, 0.95f, 1.0f);
  1354. }
  1355. decision_any_cv_.notify_all();
  1356. ROS_DEBUG_STREAM_THROTTLE(10, "c2 fitCylinder completed");
  1357. // 记录 C2 拟合结果
  1358. {
  1359. static std::ofstream log_c2_fit("/home/zxy/results/c2_fit_result.log", std::ios::app);
  1360. static bool header_written_c2 = false;
  1361. if (!header_written_c2 && log_c2_fit.is_open())
  1362. {
  1363. log_c2_fit << "timestamp delay_time bottomCenter_x bottomCenter_y bottomCenter_z axis_x axis_y axis_z elevation azimuth fitResidual valid cloudNumber is_predict IsMeasure height_source" << std::endl;
  1364. log_c2_fit.flush();
  1365. header_written_c2 = true;
  1366. }
  1367. if (log_c2_fit.is_open())
  1368. {
  1369. log_c2_fit << std::fixed << std::setprecision(6)
  1370. << pose.timestamp << " "
  1371. << pose.delay_time << " "
  1372. << pose.bottomCenter.x() << " " << pose.bottomCenter.y() << " " << pose.bottomCenter.z() << " "
  1373. << pose.axis.x() << " " << pose.axis.y() << " " << pose.axis.z() << " "
  1374. << pose.elevation_angle << " "
  1375. << pose.azimuth_angle << " "
  1376. << pose.fitResidual << " "
  1377. << (int)pose.valid << " "
  1378. << pose.cloudNumber << " "
  1379. << (int)pose.is_predict << " "
  1380. << (int)pose.IsMeasure << " "
  1381. << pose.bottom_height_source << std::endl;
  1382. log_c2_fit.flush();
  1383. }
  1384. }
  1385. return pose;
  1386. };
  1387. c2_fit_tasks_++;
  1388. c2_fit_pool_.AddTask(std::move(fit_task));
  1389. }
  1390. catch (const std::exception &e)
  1391. {
  1392. ROS_ERROR("c2 async fit task submission failed: %s", e.what());
  1393. }
  1394. }
  1395. sensor_msgs::PointCloud2 output_msg;
  1396. pcl::toROSMsg(rocket_cloud, output_msg);
  1397. output_msg.header = data.header;
  1398. output_msg.header.frame_id = "map";
  1399. if (ros::ok())
  1400. {
  1401. c2_pub_.publish(output_msg);
  1402. }
  1403. c2_frames_++;
  1404. if ((c2_frames_ % 100 == 0) && ros::Time::now() - last_stat_time_ > ros::Duration(1.0))
  1405. {
  1406. ROS_INFO_STREAM("[STAT] C2 frames=" << c2_frames_.load() << " fit_tasks=" << c2_fit_tasks_.load());
  1407. last_stat_time_ = ros::Time::now();
  1408. }
  1409. }
  1410. }
  1411. fitting_enabled_.store(false, std::memory_order_relaxed);
  1412. ROS_INFO("拼接线程已正常退出");
  1413. }
  1414. // 单机1四个雷达的点云处理函数:包括坐标转换和ROI提取
  1415. CloudType LidarFusionNode::c1_funcLidar1(const sensor_msgs::PointCloud2ConstPtr &cloud)
  1416. {
  1417. CloudType local_cloud;
  1418. pcl::fromROSMsg(*cloud, local_cloud);
  1419. TransformPointCloud(local_cloud, local_cloud, C1T1_to_Shipf_);
  1420. extractROI(local_cloud, roi_1);
  1421. return local_cloud;
  1422. }
  1423. CloudType LidarFusionNode::c1_funcLidar2(const sensor_msgs::PointCloud2ConstPtr &cloud)
  1424. {
  1425. CloudType local_cloud;
  1426. pcl::fromROSMsg(*cloud, local_cloud);
  1427. TransformPointCloud(local_cloud, local_cloud, C1T2_to_Shipf_);
  1428. extractROI(local_cloud, roi_1);
  1429. return local_cloud;
  1430. }
  1431. CloudType LidarFusionNode::c1_funcLidar3(const sensor_msgs::PointCloud2ConstPtr &cloud)
  1432. {
  1433. CloudType local_cloud;
  1434. pcl::fromROSMsg(*cloud, local_cloud);
  1435. TransformPointCloud(local_cloud, local_cloud, C1T3_to_Shipf_);
  1436. extractROI(local_cloud, roi_1);
  1437. return local_cloud;
  1438. }
  1439. CloudType LidarFusionNode::c1_funcLidar4(const sensor_msgs::PointCloud2ConstPtr &cloud)
  1440. {
  1441. CloudType local_cloud;
  1442. pcl::fromROSMsg(*cloud, local_cloud);
  1443. TransformPointCloud(local_cloud, local_cloud, C1T4_to_Shipf_);
  1444. extractROI(local_cloud, roi_1);
  1445. return local_cloud;
  1446. }
  1447. CloudType LidarFusionNode::c2_funcLidar1(const sensor_msgs::PointCloud2ConstPtr &cloud)
  1448. {
  1449. CloudType local_cloud;
  1450. pcl::fromROSMsg(*cloud, local_cloud);
  1451. TransformPointCloud(local_cloud, local_cloud, C2T1_to_Shipf_);
  1452. extractROI(local_cloud, roi_2);
  1453. return local_cloud;
  1454. }
  1455. CloudType LidarFusionNode::c2_funcLidar2(const sensor_msgs::PointCloud2ConstPtr &cloud)
  1456. {
  1457. CloudType local_cloud;
  1458. pcl::fromROSMsg(*cloud, local_cloud);
  1459. TransformPointCloud(local_cloud, local_cloud, C2T2_to_Shipf_);
  1460. extractROI(local_cloud, roi_2);
  1461. return local_cloud;
  1462. }
  1463. CloudType LidarFusionNode::c2_funcLidar3(const sensor_msgs::PointCloud2ConstPtr &cloud)
  1464. {
  1465. CloudType local_cloud;
  1466. pcl::fromROSMsg(*cloud, local_cloud);
  1467. TransformPointCloud(local_cloud, local_cloud, C2T3_to_Shipf_);
  1468. extractROI(local_cloud, roi_2);
  1469. return local_cloud;
  1470. }
  1471. CloudType LidarFusionNode::c2_funcLidar4(const sensor_msgs::PointCloud2ConstPtr &cloud)
  1472. {
  1473. CloudType local_cloud;
  1474. pcl::fromROSMsg(*cloud, local_cloud);
  1475. TransformPointCloud(local_cloud, local_cloud, C2T4_to_Shipf_);
  1476. extractROI(local_cloud, roi_2);
  1477. return local_cloud;
  1478. }
  1479. // Rocket点云提取函数:对合并后的点云进行Rocket点云提取处理
  1480. CloudType LidarFusionNode::rocketExtract(const CloudType &cloud, const std::array<float, 6> &roi, double gps_timestamp)
  1481. {
  1482. bool useFilter = true;
  1483. if (useFilter)
  1484. {
  1485. // TicToc t_filter;
  1486. // 先利用网格降采样
  1487. float rocketRadius = params_.rocket_radius;
  1488. pcl::PointCloud<PointType> tempCloud = cloud;
  1489. // cout<<"rocket_extract_voxel_ratio_ "<< rocket_extract_voxel_ratio_<<endl;
  1490. voxel_filter(tempCloud, rocketRadius * static_cast<float>(rocket_extract_voxel_ratio_));
  1491. // std::cout<<"Rocket Extract voxel_filter: "<<t_filter.toc()<<" ms"<<std::endl;
  1492. (void)gps_timestamp; // unused in clustering path, retained for interface compatibility
  1493. // TicToc t_rope;
  1494. // 绳索滤除:在指定 ROI 内用 PCA 线性度去除绳索点云
  1495. CloudType result_cloud;
  1496. if (1)
  1497. {
  1498. if (!cloud.empty())
  1499. {
  1500. result_cloud = FilterRopeByLinearity(
  1501. tempCloud,
  1502. rope_filter_roi_,
  1503. /*cluster_tolerance=*/0.3f,
  1504. /*min_cluster_size=*/5,
  1505. /*linearity_thresh=*/static_cast<float>(rope_filter_linearity_thresh_),
  1506. /*max_cross_radius=*/0.15f);
  1507. }
  1508. }
  1509. // std::cout<<"Rocket Extract FilterRopeByLinearity: "<<t_rope.toc()<<" ms"<<std::endl;
  1510. // TicToc t_cluster;
  1511. // 2. 聚类并保留点数最多的点云块
  1512. const double cluster_threshold = rocket_cluster_threshold_; // 欧式聚类距离阈值(米)
  1513. const int min_cluster_size = rocket_cluster_min_size_; // 最小有效聚类点数
  1514. // cout<<"cluster threshold "<< cluster_threshold<< " min_cluster_size"<< min_cluster_size<<endl;
  1515. result_cloud = clusterKeepLargest(result_cloud, cluster_threshold, min_cluster_size);
  1516. if (result_cloud.empty())
  1517. {
  1518. return CloudType();
  1519. }
  1520. // std::cout<<"Rocket Extract clusterKeepLargest: "<<t_cluster.toc()<<" ms"<<std::endl;
  1521. return result_cloud;
  1522. }
  1523. else
  1524. {
  1525. return cloud;
  1526. }
  1527. }
  1528. // 决策线程函数:从两个雷达的姿态队列中取出数据,进行决策并输出结果
  1529. void LidarFusionNode::decisionThreadLoop()
  1530. {
  1531. int csvCount = 0, simuCount = 0, realCount = 0, testCount = 0;
  1532. unsigned int recursion_time = 0, recursion_overflag = 0;
  1533. double COM_ZL[3] = {0}, pos_bottom_N[3] = {0};
  1534. double COM_V[3] = {0}, vel[3] = {0};
  1535. double COM_att[3] = {0}, att_hook[3] = {0};
  1536. double SheXiang = SheXiang_para;
  1537. double att[3] = {0}, att_net[3] = {0};
  1538. double Lever[3] = {Lever_para[0], Lever_para[1], Lever_para[2]};
  1539. double JBottom2JM_JT[3] = {JT_para[0], JT_para[1], JT_para[2]};
  1540. ros::Rate rate(100.0);
  1541. while (decision_running_.load(std::memory_order_relaxed) && ros::ok())
  1542. {
  1543. // 直接进行两组预测
  1544. PoseData result;
  1545. bool have_any = false;
  1546. const double now_sec = ros::Time::now().toSec();
  1547. // 在预测前,按时间窗口裁剪历史,避免长期无更新导致历史积压预测无法停止
  1548. // 窗口选择:2s
  1549. double hist_max_age = 2;
  1550. if (c1_predictor_)
  1551. c1_predictor_->pruneHistoryByTime(now_sec, hist_max_age);
  1552. if (c2_predictor_)
  1553. c2_predictor_->pruneHistoryByTime(now_sec, hist_max_age);
  1554. // 以“最新帧timestamp + (now - 最新delay_time)”作为各自的预测时间
  1555. double c1_last_ts = s_last_c1_stamp_sec.load(std::memory_order_relaxed);
  1556. double c2_last_ts = s_last_c2_stamp_sec.load(std::memory_order_relaxed);
  1557. double c1_last_delay = s_last_c1_delay_sec.load(std::memory_order_relaxed);
  1558. double c2_last_delay = s_last_c2_delay_sec.load(std::memory_order_relaxed);
  1559. double c1_delay = now_sec - c1_last_delay;
  1560. double c2_delay = now_sec - c2_last_delay;
  1561. double t_pred_c1 = (c1_last_ts > 0.0 && c1_last_delay > 0.0) ? (c1_last_ts + (now_sec - c1_last_delay)) : now_sec;
  1562. double t_pred_c2 = (c2_last_ts > 0.0 && c2_last_delay > 0.0) ? (c2_last_ts + (now_sec - c2_last_delay)) : now_sec;
  1563. // std::cout << "c1_last_ts = "<< std::fixed << std::setprecision(6) << c1_last_ts <<std::endl;
  1564. // std::cout << "c1_last_delay = "<< std::fixed << std::setprecision(6) << c1_last_delay <<std::endl;
  1565. // std::cout << "c1_delay = "<< std::fixed << std::setprecision(6) << c1_delay <<std::endl;
  1566. // 由 center/axis 构建 PoseData(预测值)改为调用头文件中的内联方法
  1567. PoseData c1_pred, c2_pred;
  1568. bool has_c1 = false;
  1569. bool has_c2 = false;
  1570. if (simu == 1)
  1571. {
  1572. // ROS_INFO("CAN%d csvCount = %d",this->can_interface_,csvCount);
  1573. const auto &data = csv_data_list[csvCount];
  1574. csvCount++;
  1575. if (csvCount >= print_count)
  1576. {
  1577. csvCount = 0;
  1578. }
  1579. // 仿真数据输出到 can_main & can_hpyo
  1580. can_main.setValue_coor_x(data.x);
  1581. can_main.setValue_coor_y(data.y);
  1582. can_main.setValue_coor_z(data.z);
  1583. can_main.setValue_projection_B(data.pitch);
  1584. can_main.setValue_projection_A(data.yaw);
  1585. can_main.setValue_output_delay(data.delay);
  1586. can_main.setValue_state((char)(data.radar_state));
  1587. can_main.setValue_timestate(1);
  1588. can_main.setValue_visible((char)(data.is_visible));
  1589. can_main.setValue_valid((char)(data.solve_state));
  1590. can_main.setValue_timestamp(data.timestamp * 1e3);
  1591. can_main.setValue_state_lidar((char)(data.each_lidarstate));
  1592. can_main.setValue_transplane((char)(data.is_cross_plane));
  1593. can_main.setValue_predict((char)(data.is_prediction));
  1594. can_main.setValue_state_value(0);
  1595. can_main.setValue_count(simuCount);
  1596. can_main.setValue_datasource((char)(data.data_state));
  1597. can_hpyo.setValue_coor_x(data.x);
  1598. can_hpyo.setValue_coor_y(data.y);
  1599. can_hpyo.setValue_coor_z(data.z);
  1600. can_hpyo.setValue_projection_B(data.pitch);
  1601. can_hpyo.setValue_projection_A(data.yaw);
  1602. can_hpyo.setValue_output_delay(data.delay);
  1603. can_hpyo.setValue_state((char)(data.radar_state));
  1604. can_hpyo.setValue_timestate(1);
  1605. can_hpyo.setValue_visible((char)(data.is_visible));
  1606. can_hpyo.setValue_valid((char)(data.solve_state));
  1607. can_hpyo.setValue_timestamp(data.timestamp * 1e3);
  1608. can_hpyo.setValue_state_lidar((char)(data.each_lidarstate));
  1609. can_hpyo.setValue_transplane((char)(data.is_cross_plane));
  1610. can_hpyo.setValue_predict((char)(data.is_prediction));
  1611. can_hpyo.setValue_state_value(0);
  1612. can_hpyo.setValue_count(simuCount);
  1613. can_hpyo.setValue_datasource((char)(data.data_state));
  1614. simuCount++;
  1615. if (simuCount > 255)
  1616. {
  1617. simuCount = 0;
  1618. }
  1619. }
  1620. else if (simu == 2)
  1621. {
  1622. // double COM_ZL[3] = {-100.0, -200.0, 300.0}; // 箭下传数据,单位:米
  1623. // double SheXiang = 130.0; // 射向 单位:度
  1624. // double att[3] = {5.0, -3.0, 100.0}; // 惯组输出的网系姿态,单位:度
  1625. // double Lever[3] = {1, -60, 1}; // 摇心在网系坐标系下的杆臂,单位:米
  1626. PoseData result_out;
  1627. result_out.ProjectedCenter.x() = 0;
  1628. result_out.ProjectedCenter.y() = 0;
  1629. result_out.axis.x() = 0.0;
  1630. result_out.axis.y() = 0.0;
  1631. result_out.axis.z() = 0.0;
  1632. result_out.cloudNumber = 0;
  1633. result_out.fitResidual = 0.0;
  1634. result_out.is_predict = 0.0;
  1635. // double COM_ZL[3] = {0};
  1636. // double COM_V[3] = {0};
  1637. // double COM_att[3] = {0};
  1638. // double SheXiang = SheXiang_para;
  1639. // double att[3] = {0};
  1640. // double Lever[3] = {Lever_para[0], Lever_para[1], Lever_para[2]};
  1641. // double JBottom2JM_JT[3] = {JT_para[0], JT_para[1],JT_para[2]};
  1642. recursion_time++;
  1643. if (udp_client.get_update_flag())
  1644. {
  1645. udp_client.set_update_flag(0);
  1646. recursion_time = 0;
  1647. recursion_overflag = 0;
  1648. COM_V[0] = udp_client.get_vx_value();
  1649. COM_V[1] = udp_client.get_vy_value();
  1650. COM_V[2] = udp_client.get_vz_value();
  1651. COM_ZL[0] = udp_client.get_x_value() + COM_V[0] * delay_JT_ms / 1000.0;
  1652. COM_ZL[1] = udp_client.get_y_value() + COM_V[1] * delay_JT_ms / 1000.0;
  1653. COM_ZL[2] = udp_client.get_z_value() + COM_V[2] * delay_JT_ms / 1000.0;
  1654. COM_att[0] = udp_client.get_pitch_value();
  1655. COM_att[1] = udp_client.get_yaw_value();
  1656. COM_att[2] = udp_client.get_roll_value();
  1657. can_main.setValue_predict(0x01);
  1658. can_hpyo.setValue_predict(0x01);
  1659. result_out.IsMeasure = 0x01;
  1660. }
  1661. else if (udp_client_bak.get_update_flag())
  1662. {
  1663. udp_client_bak.set_update_flag(0);
  1664. recursion_time = 0;
  1665. recursion_overflag = 0;
  1666. COM_V[0] = udp_client_bak.get_vx_value();
  1667. COM_V[1] = udp_client_bak.get_vy_value();
  1668. COM_V[2] = udp_client_bak.get_vz_value();
  1669. COM_ZL[0] = udp_client_bak.get_x_value() + COM_V[0] * delay_JT_ms / 1000.0;
  1670. COM_ZL[1] = udp_client_bak.get_y_value() + COM_V[1] * delay_JT_ms / 1000.0;
  1671. COM_ZL[2] = udp_client_bak.get_z_value() + COM_V[2] * delay_JT_ms / 1000.0;
  1672. COM_att[0] = udp_client_bak.get_pitch_value();
  1673. COM_att[1] = udp_client_bak.get_yaw_value();
  1674. COM_att[2] = udp_client_bak.get_roll_value();
  1675. can_main.setValue_predict(0x01);
  1676. can_hpyo.setValue_predict(0x01);
  1677. result_out.IsMeasure = 0x01;
  1678. }
  1679. else
  1680. {
  1681. if (recursion_time < 200)
  1682. {
  1683. recursion_overflag = 0;
  1684. // 递推
  1685. COM_ZL[0] += COM_V[0] * 0.01;
  1686. COM_ZL[1] += COM_V[1] * 0.01;
  1687. COM_ZL[2] += COM_V[2] * 0.01;
  1688. can_main.setValue_predict(0x00);
  1689. can_hpyo.setValue_predict(0x00);
  1690. result_out.IsMeasure = 0x00;
  1691. }
  1692. else
  1693. {
  1694. recursion_overflag = 1;
  1695. }
  1696. }
  1697. double ZL_distance = sqrt(COM_ZL[0] * COM_ZL[0] + COM_ZL[1] * COM_ZL[1] + COM_ZL[2] * COM_ZL[2]);
  1698. double COM_att_norm = sqrt(COM_att[0] * COM_att[0] + COM_att[1] * COM_att[1] + COM_att[2] * COM_att[2]);
  1699. if (can_main.get_rec_flag())
  1700. {
  1701. att[0] = can_main.get_pitch_value();
  1702. att[1] = can_main.get_roll_value();
  1703. att[2] = can_main.get_yaw_value();
  1704. }
  1705. else if (can_hpyo.get_rec_flag())
  1706. {
  1707. att[0] = can_hpyo.get_pitch_value();
  1708. att[1] = can_hpyo.get_roll_value();
  1709. att[2] = can_hpyo.get_yaw_value();
  1710. }
  1711. else
  1712. {
  1713. att[0] = GZ_para[0];
  1714. att[1] = GZ_para[1];
  1715. att[2] = GZ_para[2];
  1716. }
  1717. double COM_ZL_processed[3] = {COM_ZL[0], COM_ZL[1], COM_ZL[2]};
  1718. double JBottom_ZL[3] = {0};
  1719. calculate_ZL_WX(COM_ZL_processed, COM_att, JBottom2JM_JT, JBottom_ZL);
  1720. double CM_WX[3] = {0};
  1721. calculate_CM_WX(COM_ZL_processed, SheXiang, att, Lever, CM_WX);
  1722. double JBottom_WX[3] = {0};
  1723. calculate_CM_WX(JBottom_ZL, SheXiang, att, Lever, JBottom_WX);
  1724. double CM_WX_15s[3] = {CM_WX[0], -CM_WX[2], CM_WX[1]};
  1725. double JBottom_WX_15s[3] = {JBottom_WX[0], -JBottom_WX[2], JBottom_WX[1]};
  1726. double rocks[3];
  1727. double rock[3];
  1728. rocks[0] = CM_WX_15s[0] - JBottom_WX_15s[0];
  1729. rocks[1] = CM_WX_15s[1] - JBottom_WX_15s[1];
  1730. rocks[2] = CM_WX_15s[2] - JBottom_WX_15s[2];
  1731. double rock_norm = sqrt(rocks[0] * rocks[0] + rocks[1] * rocks[1] + rocks[2] * rocks[2]);
  1732. if (fabs(rock_norm) < 1e-9)
  1733. {
  1734. rock[0] = rock[1] = rock[2] = 0.0;
  1735. }
  1736. else
  1737. {
  1738. rock[0] = rocks[0] / rock_norm;
  1739. rock[1] = rocks[1] / rock_norm;
  1740. rock[2] = rocks[2] / rock_norm;
  1741. }
  1742. double azimuth_deg, elevation_deg, theta;
  1743. azimuth_deg = atan2(rock[1], rock[0]) * 180.0f / PI;
  1744. if (azimuth_deg < 0)
  1745. {
  1746. azimuth_deg += 360.0;
  1747. }
  1748. theta = acos(rock[2]) * 180.0f / PI;
  1749. elevation_deg = 90.0 - theta;
  1750. if (elevation_deg < 0)
  1751. {
  1752. elevation_deg = 0.0;
  1753. }
  1754. char flag_chuanwang = 0;
  1755. double J0_WX_15s[3] = {0.0, 0.0, 0.0};
  1756. if (JBottom_WX[1] < 0)
  1757. {
  1758. flag_chuanwang = 1;
  1759. double J0_WX[3];
  1760. double diff[3] = {
  1761. JBottom_WX[0] - CM_WX[0],
  1762. JBottom_WX[1] - CM_WX[1],
  1763. JBottom_WX[2] - CM_WX[2]};
  1764. double denominator = fabs(JBottom_WX[1]) + CM_WX[1];
  1765. if (fabs(denominator) < 1e-9)
  1766. {
  1767. J0_WX[0] = CM_WX[0];
  1768. J0_WX[1] = CM_WX[1];
  1769. J0_WX[2] = CM_WX[2];
  1770. }
  1771. else
  1772. {
  1773. double scalar = CM_WX[1] / denominator;
  1774. J0_WX[0] = diff[0] * scalar + CM_WX[0];
  1775. J0_WX[1] = diff[1] * scalar + CM_WX[1];
  1776. J0_WX[2] = diff[2] * scalar + CM_WX[2];
  1777. }
  1778. J0_WX_15s[0] = J0_WX[0];
  1779. J0_WX_15s[1] = -J0_WX[2];
  1780. J0_WX_15s[2] = JBottom_WX[1];
  1781. if ((ZL_distance < 1500.0) && (ZL_distance > 0.01) && (COM_att_norm > 0.0001))
  1782. {
  1783. can_main.setValue_visible(0x00);
  1784. can_main.setValue_valid(0x00);
  1785. can_main.setValue_transplane(flag_chuanwang);
  1786. can_hpyo.setValue_visible(0x00);
  1787. can_hpyo.setValue_valid(0x00);
  1788. can_hpyo.setValue_transplane(flag_chuanwang);
  1789. result_out.valid = 0x00;
  1790. result_out.Isvisible = 0x00;
  1791. result_out.TransPlane = flag_chuanwang;
  1792. }
  1793. else
  1794. {
  1795. can_main.setValue_visible(0x01);
  1796. can_main.setValue_valid(0x01);
  1797. can_main.setValue_transplane(0x00);
  1798. can_hpyo.setValue_visible(0x01);
  1799. can_hpyo.setValue_valid(0x01);
  1800. can_hpyo.setValue_transplane(0x00);
  1801. result_out.valid = 0x01;
  1802. result_out.Isvisible = 0x01;
  1803. result_out.TransPlane = 0x00;
  1804. }
  1805. can_main.setValue_coor_x((float)J0_WX_15s[0]);
  1806. can_main.setValue_coor_y((float)J0_WX_15s[1]);
  1807. can_main.setValue_coor_z((float)J0_WX_15s[2]);
  1808. // can_main.setValue_transplane(flag_chuanwang);
  1809. can_hpyo.setValue_coor_x((float)J0_WX_15s[0]);
  1810. can_hpyo.setValue_coor_y((float)J0_WX_15s[1]);
  1811. can_hpyo.setValue_coor_z((float)J0_WX_15s[2]);
  1812. // can_hpyo.setValue_transplane(flag_chuanwang);
  1813. result_out.bottomCenter.x() = (float)J0_WX_15s[0];
  1814. result_out.bottomCenter.y() = (float)J0_WX_15s[1];
  1815. result_out.bottomCenter.z() = (float)J0_WX_15s[2];
  1816. // result_out.TransPlane = flag_chuanwang;
  1817. }
  1818. else
  1819. {
  1820. if ((ZL_distance < 1500.0) && (ZL_distance > 0.01) && (COM_att_norm > 0.0001))
  1821. {
  1822. can_main.setValue_visible(0x00);
  1823. can_main.setValue_valid(0x00);
  1824. can_hpyo.setValue_visible(0x00);
  1825. can_hpyo.setValue_valid(0x00);
  1826. result_out.valid = 0x00;
  1827. result_out.Isvisible = 0x00;
  1828. }
  1829. else
  1830. {
  1831. can_main.setValue_visible(0x01);
  1832. can_main.setValue_valid(0x01);
  1833. can_hpyo.setValue_visible(0x01);
  1834. can_hpyo.setValue_valid(0x01);
  1835. result_out.valid = 0x01;
  1836. result_out.Isvisible = 0x01;
  1837. }
  1838. can_main.setValue_coor_x((float)JBottom_WX_15s[0]);
  1839. can_main.setValue_coor_y((float)JBottom_WX_15s[1]);
  1840. can_main.setValue_coor_z((float)JBottom_WX_15s[2]);
  1841. can_main.setValue_transplane(flag_chuanwang);
  1842. can_hpyo.setValue_coor_x((float)JBottom_WX_15s[0]);
  1843. can_hpyo.setValue_coor_y((float)JBottom_WX_15s[1]);
  1844. can_hpyo.setValue_coor_z((float)JBottom_WX_15s[2]);
  1845. can_hpyo.setValue_transplane(flag_chuanwang);
  1846. result_out.bottomCenter.x() = (float)JBottom_WX_15s[0];
  1847. result_out.bottomCenter.y() = (float)JBottom_WX_15s[1];
  1848. result_out.bottomCenter.z() = (float)JBottom_WX_15s[2];
  1849. result_out.TransPlane = flag_chuanwang;
  1850. }
  1851. // printf("azimuth_deg=%.6f\n", azimuth_deg);
  1852. // printf("elevation_deg=%.6f\n", elevation_deg);
  1853. // printf("穿网前底部中心点(网系坐标系下)结果:%.6f %.6f %.6f\n",
  1854. // JBottom_WX_15s[0], JBottom_WX_15s[1], JBottom_WX_15s[2]);
  1855. // if (flag_chuanwang == 1) {
  1856. // printf("穿网后火箭截面与网系的交点结果:%.6f %.6f %.6f\n",
  1857. // J0_WX_15s[0], J0_WX_15s[1], J0_WX_15s[2]);
  1858. // } else {
  1859. // printf("未穿网\n");
  1860. // }
  1861. if(recursion_overflag == 1)
  1862. {
  1863. can_main.setValue_visible(0x01);
  1864. can_main.setValue_valid(0x01);
  1865. can_hpyo.setValue_visible(0x01);
  1866. can_hpyo.setValue_valid(0x01);
  1867. result_out.valid = 0x01;
  1868. result_out.Isvisible = 0x01;
  1869. }
  1870. can_main.setValue_output_delay(0.0);
  1871. can_main.setValue_state(0x00);
  1872. can_main.setValue_timestate(0x00);
  1873. can_main.setValue_timestamp(0);
  1874. can_main.setValue_state_lidar(0x00);
  1875. can_main.setValue_state_value(0x00);
  1876. can_main.setValue_projection_B((float)elevation_deg);
  1877. can_main.setValue_projection_A((float)azimuth_deg);
  1878. can_main.setValue_count(testCount);
  1879. can_hpyo.setValue_output_delay(0.0);
  1880. can_hpyo.setValue_state(0x00);
  1881. can_hpyo.setValue_timestate(0x00);
  1882. can_hpyo.setValue_timestamp(0);
  1883. can_hpyo.setValue_state_lidar(0x00);
  1884. can_hpyo.setValue_state_value(0x00);
  1885. can_hpyo.setValue_projection_B((float)elevation_deg);
  1886. can_hpyo.setValue_projection_A((float)azimuth_deg);
  1887. can_hpyo.setValue_count(testCount);
  1888. result_out.timestamp = 0;
  1889. result_out.elevation_angle = (float)elevation_deg;
  1890. result_out.azimuth_angle = (float)azimuth_deg;
  1891. result_out.delay_time = 0.0;
  1892. result_out.angle_zero_state = 0x00;
  1893. result_out.each_lidar_status = 0x00;
  1894. result_out.time_sync_state = 0x00;
  1895. result_out.lidar_status = 0x00;
  1896. testCount++;
  1897. if (testCount > 255)
  1898. {
  1899. testCount = 0;
  1900. }
  1901. result_out.dataState = 1;
  1902. can_main.setValue_datasource((char)(result_out.dataState));
  1903. can_hpyo.setValue_datasource((char)(result_out.dataState));
  1904. auto now = std::chrono::system_clock::now();
  1905. // 转换为自1970年以来的毫秒数
  1906. uint64_t timestamp_ms = std::chrono::duration_cast<std::chrono::milliseconds>(
  1907. now.time_since_epoch())
  1908. .count();
  1909. // 日志记录
  1910. logger.setValue_result(result_out.timestamp,
  1911. result_out.bottomCenter.x(), result_out.bottomCenter.y(), result_out.bottomCenter.z(),
  1912. result_out.axis.x(), result_out.axis.y(), result_out.axis.z(),
  1913. result_out.azimuth_angle, result_out.elevation_angle,
  1914. result_out.cloudNumber, result_out.fitResidual, result_out.TransPlane, result_out.delay_time,
  1915. result_out.Isvisible, result_out.IsMeasure, result_out.lidar_status, (int)(result_out.each_lidar_status), result_out.valid, result_out.dataState, timestamp_ms);
  1916. }
  1917. else if (simu == 3)
  1918. {
  1919. if (c1_predictor_)
  1920. {
  1921. Eigen::Vector3f c, a;
  1922. bool predict_success = false;
  1923. // 情况1:尝试预测(仅在延迟<=30秒时)
  1924. if (c1_delay <= 30.0 && c1_predictor_->predictOnly(t_pred_c1, c, a))
  1925. {
  1926. c1_pred = makePoseFromPredict(c, a, 1, t_pred_c1);
  1927. // if(c1_time_sync_state_.load(std::memory_order_relaxed))
  1928. // {
  1929. // c1_pred.time_sync_state = 1;
  1930. // }
  1931. // else
  1932. // {
  1933. // c1_pred.time_sync_state = 0;
  1934. // }
  1935. predict_success = true;
  1936. // 根据时间逻辑设置状态
  1937. double delay_ms = c1_delay * 1000.0;
  1938. c1_pred.delay_time = delay_ms;
  1939. if (delay_ms <= 50.0)
  1940. {
  1941. c1_pred.IsMeasure = 1;
  1942. c1_pred.valid = 0; // 有效
  1943. }
  1944. else if (delay_ms <= 1000.0)
  1945. {
  1946. c1_pred.IsMeasure = 0;
  1947. c1_pred.valid = 0; // 有效(延迟在50ms到1秒之间)
  1948. }
  1949. else if (c1_delay <= 30.0)
  1950. {
  1951. c1_pred.IsMeasure = 0;
  1952. c1_pred.valid = 1; // 无效(延迟在1秒到30秒之间)
  1953. }
  1954. else
  1955. {
  1956. // 这里理论上不会执行,因为上面已经判断c1_delay <= 30.0
  1957. c1_pred.valid = 1; // 无效
  1958. c1_pred.IsMeasure = 0;
  1959. }
  1960. }
  1961. // 处理预测结果
  1962. if (predict_success)
  1963. {
  1964. if (c1_predictor_->time_first < 1e-9)
  1965. {
  1966. c1_predictor_->time_first = now_sec;
  1967. }
  1968. /*如果超过1s或者更新次数超过10次,就开始输出*/
  1969. if (c1_pred.valid == 0 && (now_sec - c1_predictor_->time_first > 1.0 || c1_predictor_->num_inter_Update >= 100))
  1970. {
  1971. // 当前预测有效:更新上一次有效结果
  1972. last_valid_result_c1_ = c1_pred;
  1973. has_c1 = true;
  1974. }
  1975. else
  1976. {
  1977. // 当前预测无效:使用上一次有效结果
  1978. if (last_valid_result_c1_.valid == 0)
  1979. { // 确保上一次结果本身有效
  1980. c1_pred = last_valid_result_c1_;
  1981. c1_pred.timestamp = t_pred_c1; // 更新时间戳为当前时刻
  1982. c1_pred.valid = 1; // 标记为无效(因为当前预测无效)
  1983. c1_pred.IsMeasure = 0; // 不是实时测量
  1984. has_c1 = true;
  1985. }
  1986. // 如果上一次结果也无效,则不输出任何结果
  1987. }
  1988. }
  1989. else
  1990. {
  1991. // 预测失败或延迟超过30秒:使用上一次有效结果
  1992. if (last_valid_result_c1_.valid == 0)
  1993. { // 确保上一次结果本身有效
  1994. c1_pred = last_valid_result_c1_;
  1995. c1_pred.timestamp = t_pred_c1; // 更新时间戳为当前时刻
  1996. c1_pred.valid = 1; // 标记为无效(因为当前没有有效预测)
  1997. c1_pred.IsMeasure = 0; // 不是实时测量
  1998. has_c1 = true;
  1999. }
  2000. // 如果上一次结果无效,则不输出任何结果
  2001. }
  2002. // 可视化
  2003. if (has_c1)
  2004. {
  2005. posedetect_vis::publishPredictCylinder(
  2006. c1_pred.bottomCenter.cast<float>(),
  2007. c1_pred.axis.cast<float>(),
  2008. static_cast<float>(params_.rocket_radius),
  2009. static_cast<float>(params_.rocket_length),
  2010. 1);
  2011. }
  2012. }
  2013. if (c2_predictor_)
  2014. {
  2015. Eigen::Vector3f c, a;
  2016. bool predict_success = false;
  2017. // 情况1:尝试预测(仅在延迟<=30秒时)
  2018. if (c2_delay <= 30.0 && c2_predictor_->predictOnly(t_pred_c2, c, a))
  2019. {
  2020. c2_pred = makePoseFromPredict(c, a, 2, t_pred_c2);
  2021. // if(c2_time_sync_state_.load(std::memory_order_relaxed))
  2022. // {
  2023. // c2_pred.time_sync_state = 1;
  2024. // }
  2025. // else
  2026. // {
  2027. // c2_pred.time_sync_state = 0;
  2028. // }
  2029. predict_success = true;
  2030. // 根据时间逻辑设置状态
  2031. double delay_ms = c2_delay * 1000.0;
  2032. c2_pred.delay_time = delay_ms;
  2033. if (delay_ms <= 50.0)
  2034. {
  2035. c2_pred.IsMeasure = 1;
  2036. c2_pred.valid = 0; // 有效
  2037. }
  2038. else if (delay_ms <= 1000.0)
  2039. {
  2040. c2_pred.IsMeasure = 0;
  2041. c2_pred.valid = 0; // 有效(延迟在50ms到1秒之间)
  2042. }
  2043. else if (c2_delay <= 30.0)
  2044. {
  2045. c2_pred.IsMeasure = 0;
  2046. c2_pred.valid = 1; // 无效(延迟在1秒到30秒之间)
  2047. }
  2048. else
  2049. {
  2050. // 这里理论上不会执行,因为上面已经判断c2_delay <= 30.0
  2051. c2_pred.valid = 1; // 无效
  2052. c2_pred.IsMeasure = 0;
  2053. }
  2054. }
  2055. // 处理预测结果
  2056. if (predict_success)
  2057. {
  2058. if (c2_predictor_->time_first < 1e-9)
  2059. {
  2060. c2_predictor_->time_first = now_sec;
  2061. }
  2062. if (c2_pred.valid == 0 && (now_sec - c2_predictor_->time_first > 1.0 || c2_predictor_->num_inter_Update >= 100))
  2063. {
  2064. // 当前预测有效:更新上一次有效结果
  2065. last_valid_result_c2_ = c2_pred;
  2066. has_c2 = true;
  2067. }
  2068. else
  2069. {
  2070. // 当前预测无效:使用上一次有效结果
  2071. if (last_valid_result_c2_.valid == 0)
  2072. { // 确保上一次结果本身有效
  2073. c2_pred = last_valid_result_c2_;
  2074. c2_pred.timestamp = t_pred_c2; // 更新时间戳为当前时刻
  2075. c2_pred.valid = 1; // 标记为无效(因为当前预测无效)
  2076. c2_pred.IsMeasure = 0; // 不是实时测量
  2077. has_c2 = true;
  2078. }
  2079. // 如果上一次结果也无效,则不输出任何结果
  2080. }
  2081. }
  2082. else
  2083. {
  2084. // 预测失败或延迟超过30秒:使用上一次有效结果
  2085. if (last_valid_result_c2_.valid == 0)
  2086. { // 确保上一次结果本身有效
  2087. c2_pred = last_valid_result_c2_;
  2088. c2_pred.timestamp = t_pred_c2; // 更新时间戳为当前时刻
  2089. c2_pred.valid = 1; // 标记为无效(因为当前没有有效预测)
  2090. c2_pred.IsMeasure = 0; // 不是实时测量
  2091. has_c2 = true;
  2092. }
  2093. // 如果上一次结果无效,则不输出任何结果
  2094. }
  2095. // 预测结果可视化(单机2)
  2096. if (has_c2)
  2097. {
  2098. posedetect_vis::publishPredictCylinder(
  2099. c2_pred.bottomCenter.cast<float>(),
  2100. c2_pred.axis.cast<float>(),
  2101. static_cast<float>(params_.rocket_radius),
  2102. static_cast<float>(params_.rocket_length),
  2103. 2);
  2104. }
  2105. }
  2106. if (has_c1 || has_c2)
  2107. {
  2108. have_any = true;
  2109. if (has_c1 && has_c2)
  2110. {
  2111. result = decideTwo(c1_pred, c2_pred);
  2112. }
  2113. else if (has_c1)
  2114. {
  2115. result = decideOne(c1_pred);
  2116. }
  2117. else
  2118. {
  2119. result = decideOne(c2_pred);
  2120. }
  2121. // 输出调试日志:c1_pred、c2_pred、result 到文件
  2122. {
  2123. static std::ofstream log_c1("/home/zxy/results/c1_pred.log", std::ios::app);
  2124. static std::ofstream log_c2("/home/zxy/results/c2_pred.log", std::ios::app);
  2125. static std::ofstream log_result("/home/zxy/results/result.log", std::ios::app);
  2126. static bool header_written = false;
  2127. if (!header_written)
  2128. {
  2129. if (log_c1.is_open())
  2130. {
  2131. log_c1 << "timestamp bottomCenter_x bottomCenter_y bottomCenter_z axis_x axis_y axis_z azimuth elevation IsMeasure valid delay" << std::endl;
  2132. log_c1.flush();
  2133. }
  2134. if (log_c2.is_open())
  2135. {
  2136. log_c2 << "timestamp bottomCenter_x bottomCenter_y bottomCenter_z axis_x axis_y axis_z azimuth elevation IsMeasure valid delay" << std::endl;
  2137. log_c2.flush();
  2138. }
  2139. if (log_result.is_open())
  2140. {
  2141. log_result << "timestamp bottomCenter_x bottomCenter_y bottomCenter_z axis_x axis_y axis_z IsMeasure valid azimuth elevation" << std::endl;
  2142. log_result.flush();
  2143. }
  2144. header_written = true;
  2145. }
  2146. if (has_c1 && log_c1.is_open())
  2147. {
  2148. log_c1 << std::fixed << std::setprecision(6)
  2149. << c1_pred.timestamp << " "
  2150. << c1_pred.bottomCenter.x() << " " << c1_pred.bottomCenter.y() << " " << c1_pred.bottomCenter.z() << " "
  2151. << c1_pred.axis.x() << " " << c1_pred.axis.y() << " " << c1_pred.axis.z() << " "
  2152. << c1_pred.azimuth_angle << " " << c1_pred.elevation_angle << " "
  2153. << (int)c1_pred.IsMeasure << " "
  2154. << (int)c1_pred.valid << " "
  2155. << c1_delay << std::endl;
  2156. log_c1.flush();
  2157. }
  2158. if (has_c2 && log_c2.is_open())
  2159. {
  2160. log_c2 << std::fixed << std::setprecision(6)
  2161. << c2_pred.timestamp << " "
  2162. << c2_pred.bottomCenter.x() << " " << c2_pred.bottomCenter.y() << " " << c2_pred.bottomCenter.z() << " "
  2163. << c2_pred.axis.x() << " " << c2_pred.axis.y() << " " << c2_pred.axis.z() << " "
  2164. << c2_pred.azimuth_angle << " " << c2_pred.elevation_angle << " "
  2165. << (int)c2_pred.IsMeasure << " "
  2166. << (int)c2_pred.valid << " "
  2167. << c2_delay << std::endl;
  2168. log_c2.flush();
  2169. }
  2170. if (have_any && log_result.is_open())
  2171. {
  2172. log_result << std::fixed << std::setprecision(6)
  2173. << result.timestamp << " "
  2174. << result.bottomCenter.x() << " " << result.bottomCenter.y() << " " << result.bottomCenter.z() << " "
  2175. << result.axis.x() << " " << result.axis.y() << " " << result.axis.z() << " "
  2176. << (int)result.IsMeasure << " "
  2177. << (int)result.valid << " "
  2178. << result.azimuth_angle << " "
  2179. << result.elevation_angle << std::endl;
  2180. log_result.flush();
  2181. }
  2182. }
  2183. // 输出到 can_main & can_hpyo
  2184. // printf("%s %f \n", "delay_time = ", result.delay_time);
  2185. // printf("%s %f \n", "timestamp = ", result.timestamp);
  2186. can_main.setValue_coor_x(result.bottomCenter.x());
  2187. can_main.setValue_coor_y(result.bottomCenter.y());
  2188. can_main.setValue_coor_z(result.bottomCenter.z());
  2189. can_main.setValue_projection_B(result.elevation_angle);
  2190. can_main.setValue_projection_A(result.azimuth_angle);
  2191. can_main.setValue_output_delay(result.delay_time);
  2192. // can_main.setValue_state((char)(result.lidar_status));
  2193. // can_main.setValue_timestate((char)(result.time_sync_state));
  2194. can_main.setValue_visible((char)(result.Isvisible));
  2195. can_main.setValue_valid((char)(result.valid));
  2196. can_main.setValue_timestamp(result.timestamp * 1e3);
  2197. // can_main.setValue_state_lidar((char)(result.each_lidar_status));
  2198. can_main.setValue_transplane((char)(result.TransPlane));
  2199. can_main.setValue_predict((char)(result.IsMeasure));
  2200. can_main.setValue_state_value((char)(result.angle_zero_state));
  2201. can_hpyo.setValue_coor_x(result.bottomCenter.x());
  2202. can_hpyo.setValue_coor_y(result.bottomCenter.y());
  2203. can_hpyo.setValue_coor_z(result.bottomCenter.z());
  2204. can_hpyo.setValue_projection_B(result.elevation_angle);
  2205. can_hpyo.setValue_projection_A(result.azimuth_angle);
  2206. can_hpyo.setValue_output_delay(result.delay_time);
  2207. // can_hpyo.setValue_state((char)(result.lidar_status));
  2208. // can_hpyo.setValue_timestate((char)(result.time_sync_state));
  2209. can_hpyo.setValue_visible((char)(result.Isvisible));
  2210. can_hpyo.setValue_valid((char)(result.valid));
  2211. can_hpyo.setValue_timestamp(result.timestamp * 1e3);
  2212. // can_hpyo.setValue_state_lidar((char)(result.each_lidar_status));
  2213. can_hpyo.setValue_transplane((char)(result.TransPlane));
  2214. can_hpyo.setValue_predict((char)(result.IsMeasure));
  2215. can_hpyo.setValue_state_value((char)(result.angle_zero_state));
  2216. }
  2217. uint8_t each_mask = 0xFF;
  2218. int overall = 1;
  2219. try
  2220. {
  2221. LidarHeart::getStatus(each_mask, overall);
  2222. result.each_lidar_status = each_mask;
  2223. result.lidar_status = overall;
  2224. }
  2225. catch (const std::exception &e)
  2226. {
  2227. ROS_WARN_THROTTLE(5.0, "LidarHeart getStatus failed: %s", e.what());
  2228. }
  2229. if ((!c1_time_sync_state_.load(std::memory_order_relaxed)) && (!c2_time_sync_state_.load(std::memory_order_relaxed)))
  2230. {
  2231. result.time_sync_state = 0;
  2232. }
  2233. else
  2234. {
  2235. result.time_sync_state = 1;
  2236. }
  2237. result.dataState = 0;
  2238. can_main.setValue_datasource((char)(result.dataState));
  2239. can_hpyo.setValue_datasource((char)(result.dataState));
  2240. can_main.setValue_timestate((char)(result.time_sync_state));
  2241. can_main.setValue_state((char)(result.lidar_status));
  2242. can_main.setValue_state_lidar((char)(result.each_lidar_status));
  2243. can_main.setValue_count(realCount);
  2244. can_hpyo.setValue_timestate((char)(result.time_sync_state));
  2245. can_hpyo.setValue_state((char)(result.lidar_status));
  2246. can_hpyo.setValue_state_lidar((char)(result.each_lidar_status));
  2247. can_hpyo.setValue_count(realCount);
  2248. realCount++;
  2249. if (realCount > 255)
  2250. {
  2251. realCount = 0;
  2252. }
  2253. auto now_lidar = std::chrono::system_clock::now();
  2254. // 转换为自1970年以来的毫秒数
  2255. uint64_t timestamp_ms_lidar = std::chrono::duration_cast<std::chrono::milliseconds>(
  2256. now_lidar.time_since_epoch())
  2257. .count();
  2258. // 日志记录
  2259. logger.setValue_result(result.timestamp,
  2260. result.bottomCenter.x(), result.bottomCenter.y(), result.bottomCenter.z(),
  2261. result.axis.x(), result.axis.y(), result.axis.z(),
  2262. result.azimuth_angle, result.elevation_angle,
  2263. result.cloudNumber, result.fitResidual, result.TransPlane, result.delay_time,
  2264. result.Isvisible, result.IsMeasure, result.lidar_status, (int)(result.each_lidar_status), result.valid, result.dataState, timestamp_ms_lidar);
  2265. }
  2266. else
  2267. { // *****************实际测量数据处理 决策逻辑开始******************
  2268. PoseData result_out;
  2269. result_out.ProjectedCenter.x() = 0;
  2270. result_out.ProjectedCenter.y() = 0;
  2271. result_out.axis.x() = 0.0;
  2272. result_out.axis.y() = 0.0;
  2273. result_out.axis.z() = 0.0;
  2274. result_out.cloudNumber = 0;
  2275. result_out.fitResidual = 0.0;
  2276. result_out.is_predict = 0.0;
  2277. // double COM_ZL[3] = {0};
  2278. // double COM_V[3] = {0};
  2279. // double COM_att[3] = {0};
  2280. // double SheXiang = SheXiang_para;
  2281. // double att[3] = {0};
  2282. // double Lever[3] = {Lever_para[0], Lever_para[1], Lever_para[2]};
  2283. // double JBottom2JM_JT[3] = {JT_para[0], JT_para[1],JT_para[2]};
  2284. recursion_time++;
  2285. if (udp_client.get_update_flag())
  2286. {
  2287. udp_client.set_update_flag(0);
  2288. recursion_time = 0;
  2289. recursion_overflag = 0;
  2290. COM_V[0] = udp_client.get_vx_value();
  2291. COM_V[1] = udp_client.get_vy_value();
  2292. COM_V[2] = udp_client.get_vz_value();
  2293. COM_ZL[0] = udp_client.get_x_value() + COM_V[0] * delay_JT_ms / 1000.0;
  2294. COM_ZL[1] = udp_client.get_y_value() + COM_V[1] * delay_JT_ms / 1000.0;
  2295. COM_ZL[2] = udp_client.get_z_value() + COM_V[2] * delay_JT_ms / 1000.0;
  2296. COM_att[0] = udp_client.get_pitch_value();
  2297. COM_att[1] = udp_client.get_yaw_value();
  2298. COM_att[2] = udp_client.get_roll_value();
  2299. att_hook[0] = udp_client.get_pitch_value();
  2300. att_hook[1] = udp_client.get_yaw_value();
  2301. att_hook[2] = udp_client.get_roll_value();
  2302. vel[0] = udp_client.get_vx_value();
  2303. vel[1] = udp_client.get_vy_value();
  2304. vel[2] = udp_client.get_vz_value();
  2305. can_main.setValue_predict(0x01);
  2306. can_hpyo.setValue_predict(0x01);
  2307. result_out.IsMeasure = 0x01;
  2308. }
  2309. else if (udp_client_bak.get_update_flag())
  2310. {
  2311. udp_client_bak.set_update_flag(0);
  2312. recursion_time = 0;
  2313. recursion_overflag = 0;
  2314. COM_V[0] = udp_client_bak.get_vx_value();
  2315. COM_V[1] = udp_client_bak.get_vy_value();
  2316. COM_V[2] = udp_client_bak.get_vz_value();
  2317. COM_ZL[0] = udp_client_bak.get_x_value() + COM_V[0] * delay_JT_ms / 1000.0;
  2318. COM_ZL[1] = udp_client_bak.get_y_value() + COM_V[1] * delay_JT_ms / 1000.0;
  2319. COM_ZL[2] = udp_client_bak.get_z_value() + COM_V[2] * delay_JT_ms / 1000.0;
  2320. COM_att[0] = udp_client_bak.get_pitch_value();
  2321. COM_att[1] = udp_client_bak.get_yaw_value();
  2322. COM_att[2] = udp_client_bak.get_roll_value();
  2323. att_hook[0] = udp_client_bak.get_pitch_value();
  2324. att_hook[1] = udp_client_bak.get_yaw_value();
  2325. att_hook[2] = udp_client_bak.get_roll_value();
  2326. vel[0] = udp_client_bak.get_vx_value();
  2327. vel[1] = udp_client_bak.get_vy_value();
  2328. vel[2] = udp_client_bak.get_vz_value();
  2329. can_main.setValue_predict(0x01);
  2330. can_hpyo.setValue_predict(0x01);
  2331. result_out.IsMeasure = 0x01;
  2332. }
  2333. else
  2334. {
  2335. if (recursion_time < 200)
  2336. {
  2337. recursion_overflag = 0;
  2338. // 递推
  2339. COM_ZL[0] += COM_V[0] * 0.01;
  2340. COM_ZL[1] += COM_V[1] * 0.01;
  2341. COM_ZL[2] += COM_V[2] * 0.01;
  2342. can_main.setValue_predict(0x00);
  2343. can_hpyo.setValue_predict(0x00);
  2344. result_out.IsMeasure = 0x00;
  2345. }
  2346. else
  2347. {
  2348. recursion_overflag = 1;
  2349. }
  2350. }
  2351. double ZL_distance = sqrt(COM_ZL[0] * COM_ZL[0] + COM_ZL[1] * COM_ZL[1] + COM_ZL[2] * COM_ZL[2]);
  2352. double COM_att_norm = sqrt(COM_att[0] * COM_att[0] + COM_att[1] * COM_att[1] + COM_att[2] * COM_att[2]);
  2353. if (can_main.get_rec_flag())
  2354. {
  2355. att[0] = can_main.get_pitch_value();
  2356. att[1] = can_main.get_roll_value();
  2357. att[2] = can_main.get_yaw_value();
  2358. att_net[0] = can_main.get_pitch_value();
  2359. att_net[1] = can_main.get_roll_value();
  2360. att_net[2] = can_main.get_yaw_value();
  2361. }
  2362. else if (can_hpyo.get_rec_flag())
  2363. {
  2364. att[0] = can_hpyo.get_pitch_value();
  2365. att[1] = can_hpyo.get_roll_value();
  2366. att[2] = can_hpyo.get_yaw_value();
  2367. att_net[0] = can_hpyo.get_pitch_value();
  2368. att_net[1] = can_hpyo.get_roll_value();
  2369. att_net[2] = can_hpyo.get_yaw_value();
  2370. }
  2371. else
  2372. {
  2373. att[0] = GZ_para[0];
  2374. att[1] = GZ_para[1];
  2375. att[2] = GZ_para[2];
  2376. att_net[0] = GZ_para[0];
  2377. att_net[1] = GZ_para[1];
  2378. att_net[2] = GZ_para[2];
  2379. }
  2380. double COM_ZL_processed[3] = {COM_ZL[0], COM_ZL[1], COM_ZL[2]};
  2381. double JBottom_ZL[3] = {0};
  2382. calculate_ZL_WX(COM_ZL_processed, COM_att, JBottom2JM_JT, JBottom_ZL);
  2383. double CM_WX[3] = {0};
  2384. calculate_CM_WX(COM_ZL_processed, SheXiang, att, Lever, CM_WX);
  2385. double JBottom_WX[3] = {0};
  2386. calculate_CM_WX(JBottom_ZL, SheXiang, att, Lever, JBottom_WX);
  2387. double CM_WX_15s[3] = {CM_WX[0], -CM_WX[2], CM_WX[1]};
  2388. double JBottom_WX_15s[3] = {JBottom_WX[0], -JBottom_WX[2], JBottom_WX[1]};
  2389. double rocks[3];
  2390. double rock[3];
  2391. rocks[0] = CM_WX_15s[0] - JBottom_WX_15s[0];
  2392. rocks[1] = CM_WX_15s[1] - JBottom_WX_15s[1];
  2393. rocks[2] = CM_WX_15s[2] - JBottom_WX_15s[2];
  2394. double rock_norm = sqrt(rocks[0] * rocks[0] + rocks[1] * rocks[1] + rocks[2] * rocks[2]);
  2395. if (fabs(rock_norm) < 1e-9)
  2396. {
  2397. rock[0] = rock[1] = rock[2] = 0.0;
  2398. }
  2399. else
  2400. {
  2401. rock[0] = rocks[0] / rock_norm;
  2402. rock[1] = rocks[1] / rock_norm;
  2403. rock[2] = rocks[2] / rock_norm;
  2404. }
  2405. double azimuth_deg, elevation_deg, theta;
  2406. azimuth_deg = atan2(rock[1], rock[0]) * 180.0f / PI;
  2407. if (azimuth_deg < 0)
  2408. {
  2409. azimuth_deg += 360.0;
  2410. }
  2411. theta = acos(rock[2]) * 180.0f / PI;
  2412. elevation_deg = 90.0 - theta;
  2413. if (elevation_deg < 0)
  2414. {
  2415. elevation_deg = 0.0;
  2416. }
  2417. char flag_chuanwang = 0;
  2418. double J0_WX_15s[3] = {0.0, 0.0, 0.0};
  2419. if (JBottom_WX[1] < 0)
  2420. {
  2421. flag_chuanwang = 1;
  2422. double J0_WX[3];
  2423. double diff[3] = {
  2424. JBottom_WX[0] - CM_WX[0],
  2425. JBottom_WX[1] - CM_WX[1],
  2426. JBottom_WX[2] - CM_WX[2]};
  2427. double denominator = fabs(JBottom_WX[1]) + CM_WX[1];
  2428. if (fabs(denominator) < 1e-9)
  2429. {
  2430. J0_WX[0] = CM_WX[0];
  2431. J0_WX[1] = CM_WX[1];
  2432. J0_WX[2] = CM_WX[2];
  2433. }
  2434. else
  2435. {
  2436. double scalar = CM_WX[1] / denominator;
  2437. J0_WX[0] = diff[0] * scalar + CM_WX[0];
  2438. J0_WX[1] = diff[1] * scalar + CM_WX[1];
  2439. J0_WX[2] = diff[2] * scalar + CM_WX[2];
  2440. }
  2441. J0_WX_15s[0] = J0_WX[0];
  2442. J0_WX_15s[1] = -J0_WX[2];
  2443. J0_WX_15s[2] = JBottom_WX[1];
  2444. if ((ZL_distance < 1500.0) && (ZL_distance > 0.01) && (COM_att_norm > 0.0001))
  2445. {
  2446. result_out.valid = 0x00;
  2447. result_out.Isvisible = 0x00;
  2448. result_out.TransPlane = flag_chuanwang;
  2449. }
  2450. else
  2451. {
  2452. result_out.valid = 0x01;
  2453. result_out.Isvisible = 0x01;
  2454. result_out.TransPlane = 0x00;
  2455. }
  2456. result_out.bottomCenter.x() = (float)J0_WX_15s[0];
  2457. result_out.bottomCenter.y() = (float)J0_WX_15s[1];
  2458. result_out.bottomCenter.z() = (float)J0_WX_15s[2];
  2459. // result_out.TransPlane = flag_chuanwang;
  2460. }
  2461. else
  2462. {
  2463. if ((ZL_distance < 1500.0) && (ZL_distance > 0.01) && (COM_att_norm > 0.0001))
  2464. {
  2465. result_out.valid = 0x00;
  2466. result_out.Isvisible = 0x00;
  2467. }
  2468. else
  2469. {
  2470. can_main.setValue_visible(0x01);
  2471. can_main.setValue_valid(0x01);
  2472. can_hpyo.setValue_visible(0x01);
  2473. can_hpyo.setValue_valid(0x01);
  2474. result_out.valid = 0x01;
  2475. result_out.Isvisible = 0x01;
  2476. }
  2477. result_out.bottomCenter.x() = (float)JBottom_WX_15s[0];
  2478. result_out.bottomCenter.y() = (float)JBottom_WX_15s[1];
  2479. result_out.bottomCenter.z() = (float)JBottom_WX_15s[2];
  2480. result_out.TransPlane = flag_chuanwang;
  2481. }
  2482. if(recursion_overflag == 1)
  2483. {
  2484. can_main.setValue_visible(0x01);
  2485. can_main.setValue_valid(0x01);
  2486. can_hpyo.setValue_visible(0x01);
  2487. can_hpyo.setValue_valid(0x01);
  2488. result_out.valid = 0x01;
  2489. result_out.Isvisible = 0x01;
  2490. }
  2491. result_out.timestamp = 0;
  2492. result_out.elevation_angle = (float)elevation_deg;
  2493. result_out.azimuth_angle = (float)azimuth_deg;
  2494. result_out.delay_time = 0.0;
  2495. result_out.angle_zero_state = 0x00;
  2496. result_out.each_lidar_status = 0x00;
  2497. result_out.time_sync_state = 0x00;
  2498. result_out.lidar_status = 0x00;
  2499. testCount++;
  2500. if (testCount > 255)
  2501. {
  2502. testCount = 0;
  2503. }
  2504. if (c1_predictor_)
  2505. {
  2506. Eigen::Vector3f c, a;
  2507. bool predict_success = false;
  2508. if (c1_delay <= 30.0 && c1_predictor_->predictOnly(t_pred_c1, c, a))
  2509. {
  2510. c1_pred = makePoseFromPredict(c, a, 1, t_pred_c1);
  2511. predict_success = true;
  2512. double delay_ms = c1_delay * 1000.0;
  2513. c1_pred.delay_time = delay_ms;
  2514. if (delay_ms <= 50.0)
  2515. {
  2516. c1_pred.IsMeasure = 1;
  2517. c1_pred.valid = 0;
  2518. }
  2519. else if (delay_ms <= 1000.0)
  2520. {
  2521. c1_pred.IsMeasure = 0;
  2522. c1_pred.valid = 0;
  2523. }
  2524. else if (c1_delay <= 30.0)
  2525. {
  2526. c1_pred.IsMeasure = 0;
  2527. c1_pred.valid = 1;
  2528. }
  2529. else
  2530. {
  2531. c1_pred.valid = 1;
  2532. c1_pred.IsMeasure = 0;
  2533. }
  2534. }
  2535. if (predict_success)
  2536. {
  2537. if (c1_predictor_->time_first < 1e-9)
  2538. {
  2539. c1_predictor_->time_first = now_sec;
  2540. }
  2541. /*如果超过1s或者更新次数超过10次,就开始输出*/
  2542. if (c1_pred.valid == 0 && (now_sec - c1_predictor_->time_first > 1.0 || c1_predictor_->num_inter_Update >= 100))
  2543. {
  2544. // 当前预测有效:更新上一次有效结果
  2545. last_valid_result_c1_ = c1_pred;
  2546. has_c1 = true;
  2547. }
  2548. else
  2549. {
  2550. if (last_valid_result_c1_.valid == 0)
  2551. {
  2552. c1_pred = last_valid_result_c1_;
  2553. c1_pred.timestamp = t_pred_c1; // 更新时间戳为当前时刻
  2554. c1_pred.valid = 1; // 标记为无效(因为当前预测无效)
  2555. c1_pred.IsMeasure = 0; // 不是实时测量
  2556. has_c1 = true;
  2557. }
  2558. }
  2559. }
  2560. else
  2561. {
  2562. if (last_valid_result_c1_.valid == 0)
  2563. {
  2564. c1_pred = last_valid_result_c1_;
  2565. c1_pred.timestamp = t_pred_c1; // 更新时间戳为当前时刻
  2566. c1_pred.valid = 1; // 标记为无效(因为当前没有有效预测)
  2567. c1_pred.IsMeasure = 0; // 不是实时测量
  2568. has_c1 = true;
  2569. }
  2570. }
  2571. if (has_c1)
  2572. {
  2573. posedetect_vis::publishPredictCylinder(
  2574. c1_pred.bottomCenter.cast<float>(),
  2575. c1_pred.axis.cast<float>(),
  2576. static_cast<float>(params_.rocket_radius),
  2577. static_cast<float>(params_.rocket_length),
  2578. 1);
  2579. }
  2580. }
  2581. if (c2_predictor_)
  2582. {
  2583. Eigen::Vector3f c, a;
  2584. bool predict_success = false;
  2585. if (c2_delay <= 30.0 && c2_predictor_->predictOnly(t_pred_c2, c, a))
  2586. {
  2587. c2_pred = makePoseFromPredict(c, a, 2, t_pred_c2);
  2588. predict_success = true;
  2589. double delay_ms = c2_delay * 1000.0;
  2590. c2_pred.delay_time = delay_ms;
  2591. if (delay_ms <= 50.0)
  2592. {
  2593. c2_pred.IsMeasure = 1;
  2594. c2_pred.valid = 0;
  2595. }
  2596. else if (delay_ms <= 1000.0)
  2597. {
  2598. c2_pred.IsMeasure = 0;
  2599. c2_pred.valid = 0;
  2600. }
  2601. else if (c2_delay <= 30.0)
  2602. {
  2603. c2_pred.IsMeasure = 0;
  2604. c2_pred.valid = 1;
  2605. }
  2606. else
  2607. {
  2608. c2_pred.valid = 1;
  2609. c2_pred.IsMeasure = 0;
  2610. }
  2611. }
  2612. if (predict_success)
  2613. {
  2614. if (c2_predictor_->time_first < 1e-9)
  2615. {
  2616. c2_predictor_->time_first = now_sec;
  2617. }
  2618. if (c2_pred.valid == 0 && (now_sec - c2_predictor_->time_first > 1.0 || c2_predictor_->num_inter_Update >= 100))
  2619. {
  2620. // 当前预测有效:更新上一次有效结果
  2621. last_valid_result_c2_ = c2_pred;
  2622. has_c2 = true;
  2623. }
  2624. else
  2625. {
  2626. if (last_valid_result_c2_.valid == 0)
  2627. {
  2628. c2_pred = last_valid_result_c2_;
  2629. c2_pred.timestamp = t_pred_c2;
  2630. c2_pred.valid = 1;
  2631. c2_pred.IsMeasure = 0;
  2632. has_c2 = true;
  2633. }
  2634. }
  2635. }
  2636. else
  2637. {
  2638. if (last_valid_result_c2_.valid == 0)
  2639. {
  2640. c2_pred = last_valid_result_c2_;
  2641. c2_pred.timestamp = t_pred_c2;
  2642. c2_pred.valid = 1;
  2643. c2_pred.IsMeasure = 0;
  2644. has_c2 = true;
  2645. }
  2646. }
  2647. if (has_c2)
  2648. {
  2649. posedetect_vis::publishPredictCylinder(
  2650. c2_pred.bottomCenter.cast<float>(),
  2651. c2_pred.axis.cast<float>(),
  2652. static_cast<float>(params_.rocket_radius),
  2653. static_cast<float>(params_.rocket_length),
  2654. 2);
  2655. }
  2656. }
  2657. if (has_c1 || has_c2)
  2658. {
  2659. have_any = true;
  2660. if (has_c1 && has_c2)
  2661. {
  2662. result = decideTwo(c1_pred, c2_pred);
  2663. }
  2664. else if (has_c1)
  2665. {
  2666. result = decideOne(c1_pred);
  2667. }
  2668. else
  2669. {
  2670. result = decideOne(c2_pred);
  2671. }
  2672. }
  2673. uint8_t each_mask = 0xFF;
  2674. int overall = 1;
  2675. try
  2676. {
  2677. LidarHeart::getStatus(each_mask, overall);
  2678. result.each_lidar_status = each_mask;
  2679. result.lidar_status = overall;
  2680. }
  2681. catch (const std::exception &e)
  2682. {
  2683. ROS_WARN_THROTTLE(5.0, "LidarHeart getStatus failed: %s", e.what());
  2684. }
  2685. if ((!c1_time_sync_state_.load(std::memory_order_relaxed)) && (!c2_time_sync_state_.load(std::memory_order_relaxed)))
  2686. {
  2687. result.time_sync_state = 0;
  2688. }
  2689. else
  2690. {
  2691. result.time_sync_state = 1;
  2692. }
  2693. realCount++;
  2694. if (realCount > 255)
  2695. {
  2696. realCount = 0;
  2697. }
  2698. // fusion New code
  2699. result_out.dataState = 1;
  2700. result.dataState = 0;
  2701. // pos_bottom_N[0] = result.bottomCenter.x();
  2702. // pos_bottom_N[1] = result.bottomCenter.y();
  2703. // pos_bottom_N[2] = result.bottomCenter.z();
  2704. static PoseData result_fusion_out;
  2705. static float update_h = 200.0; //必须比较高
  2706. static int valid_cnt = 0;
  2707. static float old_result_xyz[3] = {0.0, 0.0, 0.0};
  2708. static double ipos_bottom_N[3] = {0.0, 0.0, 200.0};
  2709. //更新update_h高度.默认值200
  2710. if(result.valid == 0)
  2711. {
  2712. update_h = result.bottomCenter.z();
  2713. }else if(result_out.valid == 0)
  2714. {
  2715. update_h = result_out.bottomCenter.z();
  2716. }
  2717. result_fusion_out = result_out;//默认使用J上下传数据结果
  2718. if( (update_h<1500) && (update_h>110)){
  2719. if(result_out.valid == 0){
  2720. result_fusion_out = result_out;
  2721. ipos_bottom_N[0] = result_out.bottomCenter.x();
  2722. ipos_bottom_N[1] = result_out.bottomCenter.y();
  2723. ipos_bottom_N[2] = result_out.bottomCenter.z();
  2724. update_h = result_out.bottomCenter.z();
  2725. }
  2726. }else if(update_h <= 110){
  2727. result_fusion_out.valid = 1; //默认状态无效
  2728. if (result.valid == 0) //一旦有新的有效的位姿数据就更新ipos_bottom_N
  2729. {
  2730. valid_cnt = 1;
  2731. result_fusion_out = result;
  2732. result_fusion_out.valid = 0;
  2733. update_h = result_fusion_out.bottomCenter.z();
  2734. ipos_bottom_N[0] = result.bottomCenter.x();
  2735. ipos_bottom_N[1] = result.bottomCenter.y();
  2736. ipos_bottom_N[2] = result.bottomCenter.z();
  2737. }
  2738. else
  2739. {
  2740. // if (valid_cnt == 1) 不论如何也要递推计算
  2741. {
  2742. //result_fusion_out = result;
  2743. //result_fusion_out.valid = 0;
  2744. // 递推 在pos_bottom_N基础上递推
  2745. //double CM_WX_15s[3] = {CM_WX[0], -CM_WX[2], CM_WX[1]};
  2746. double pos_hook[3] = {0}, pos_hook_N_new[3] = {0}, pos_bottom_N_new[3] = {0};
  2747. double pos_hook_N_new_1b[3] = {0}, pos_bottom_N_new_1b[3] = {0};
  2748. double ipos_bottom_N_1b[3] = {ipos_bottom_N[0], ipos_bottom_N[2], -ipos_bottom_N[1]};
  2749. posbottomN2poshookL(ipos_bottom_N_1b, att_hook, att_net, pos_hook);
  2750. pos_hook[0] += vel[0] * 0.01;
  2751. pos_hook[1] += vel[1] * 0.01;
  2752. pos_hook[2] += vel[2] * 0.01;
  2753. poshookL2posbottomN(pos_hook, att_hook, att_net, pos_bottom_N_new_1b, pos_hook_N_new_1b);
  2754. pos_bottom_N_new = {pos_bottom_N_new_1b[0], -pos_bottom_N_new_1b[2], pos_bottom_N_new_1b[1]};
  2755. pos_hook_N_new = {pos_hook_N_new_1b[0], -pos_hook_N_new_1b[2], pos_hook_N_new_1b[1]};
  2756. ipos_bottom_N[0] = pos_bottom_N_new[0];
  2757. ipos_bottom_N[1] = pos_bottom_N_new[1];
  2758. ipos_bottom_N[2] = pos_bottom_N_new[2];
  2759. getRockDirectionAndFlags(pos_hook_N_new, pos_bottom_N_new,
  2760. &azimuth_deg, &elevation_deg, J0_WX_15s,
  2761. &flag_chuanwang);
  2762. if (flag_chuanwang == 0)
  2763. {
  2764. result_fusion_out.bottomCenter.x() = pos_bottom_N_new[0];
  2765. result_fusion_out.bottomCenter.y() = pos_bottom_N_new[1];
  2766. result_fusion_out.bottomCenter.z() = pos_bottom_N_new[2];
  2767. }
  2768. else
  2769. {
  2770. result_fusion_out.bottomCenter.x() = J0_WX_15s[0];
  2771. result_fusion_out.bottomCenter.y() = J0_WX_15s[1];
  2772. result_fusion_out.bottomCenter.z() = J0_WX_15s[2];
  2773. }
  2774. result_fusion_out.azimuth_angle = azimuth_deg;
  2775. result_fusion_out.elevation_angle = elevation_deg;
  2776. result_fusion_out.TransPlane = flag_chuanwang;
  2777. update_h = result_fusion_out.bottomCenter.z();
  2778. }
  2779. }
  2780. if (update_h <= 60 )
  2781. {
  2782. //result_fusion_out = result_out;
  2783. result_fusion_out.valid = 0;
  2784. //update_h = result_fusion_out.bottomCenter.z();
  2785. }
  2786. else
  2787. {
  2788. //result_fusion_out = result_out;
  2789. result_fusion_out.valid = 1;
  2790. //update_h = result_fusion_out.bottomCenter.z();
  2791. }
  2792. }
  2793. can_main.setValue_coor_x(result_fusion_out.bottomCenter.x());
  2794. can_main.setValue_coor_y(result_fusion_out.bottomCenter.y());
  2795. can_main.setValue_coor_z(result_fusion_out.bottomCenter.z());
  2796. can_main.setValue_projection_B(result_fusion_out.elevation_angle);
  2797. can_main.setValue_projection_A(result_fusion_out.azimuth_angle);
  2798. can_main.setValue_output_delay(result_fusion_out.delay_time);
  2799. can_main.setValue_state((char)(result_fusion_out.lidar_status));
  2800. can_main.setValue_timestate((char)(result_fusion_out.time_sync_state));
  2801. can_main.setValue_visible((char)(result_fusion_out.Isvisible));
  2802. can_main.setValue_valid((char)(result_fusion_out.valid));
  2803. can_main.setValue_timestamp(result_fusion_out.timestamp * 1e3);
  2804. can_main.setValue_state_lidar((char)(result_fusion_out.each_lidar_status));
  2805. can_main.setValue_transplane((char)(result_fusion_out.TransPlane));
  2806. can_main.setValue_predict((char)(result_fusion_out.IsMeasure));
  2807. can_main.setValue_state_value((char)(result_fusion_out.angle_zero_state));
  2808. can_main.setValue_datasource((char)(result_fusion_out.dataState));
  2809. can_main.setValue_count(testCount);
  2810. can_hpyo.setValue_coor_x(result_fusion_out.bottomCenter.x());
  2811. can_hpyo.setValue_coor_y(result_fusion_out.bottomCenter.y());
  2812. can_hpyo.setValue_coor_z(result_fusion_out.bottomCenter.z());
  2813. can_hpyo.setValue_projection_B(result_fusion_out.elevation_angle);
  2814. can_hpyo.setValue_projection_A(result_fusion_out.azimuth_angle);
  2815. can_hpyo.setValue_output_delay(result_fusion_out.delay_time);
  2816. can_hpyo.setValue_state((char)(result_fusion_out.lidar_status));
  2817. can_hpyo.setValue_timestate((char)(result_fusion_out.time_sync_state));
  2818. can_hpyo.setValue_visible((char)(result_fusion_out.Isvisible));
  2819. can_hpyo.setValue_valid((char)(result_fusion_out.valid));
  2820. can_hpyo.setValue_timestamp(result_fusion_out.timestamp * 1e3);
  2821. can_hpyo.setValue_state_lidar((char)(result_fusion_out.each_lidar_status));
  2822. can_hpyo.setValue_transplane((char)(result_fusion_out.TransPlane));
  2823. can_hpyo.setValue_predict((char)(result_fusion_out.IsMeasure));
  2824. can_hpyo.setValue_state_value((char)(result_fusion_out.angle_zero_state));
  2825. can_hpyo.setValue_datasource((char)(result_fusion_out.dataState));
  2826. can_main.setValue_count(testCount);
  2827. auto now_fusion_lidar = std::chrono::system_clock::now();
  2828. // 转换为自1970年以来的毫秒数
  2829. uint64_t timestamp_ms_fusion = std::chrono::duration_cast<std::chrono::milliseconds>(
  2830. now_fusion_lidar.time_since_epoch())
  2831. .count();
  2832. // 日志记录
  2833. logger.setValue_result(result_fusion_out.timestamp,
  2834. result_fusion_out.bottomCenter.x(), result_fusion_out.bottomCenter.y(), result_fusion_out.bottomCenter.z(),
  2835. result_fusion_out.axis.x(), result_fusion_out.axis.y(), result_fusion_out.axis.z(),
  2836. result_fusion_out.azimuth_angle, result_fusion_out.elevation_angle,
  2837. result_fusion_out.cloudNumber, result_fusion_out.fitResidual, result_fusion_out.TransPlane, result_fusion_out.delay_time,
  2838. result_fusion_out.Isvisible, result_fusion_out.IsMeasure, result_fusion_out.lidar_status, (int)(result_fusion_out.each_lidar_status), result_fusion_out.valid, result_fusion_out.dataState, timestamp_ms_fusion);
  2839. }
  2840. // 实时模式下触发 CAN 发送(实时模式不会启动回放线程)
  2841. can_main.triggerSendRealtime();
  2842. can_hpyo.triggerSendRealtime();
  2843. ros::spinOnce();
  2844. rate.sleep();
  2845. }
  2846. }
  2847. void LidarFusionNode::getRockDirectionAndFlags(double CM_WX_15s[3], double JBottom_WX_15s[3],
  2848. double* rt_azimuth_deg, double* rt_elevation_deg,double J0_WX_15s[3],
  2849. char* rt_flag_chuanwang)
  2850. {
  2851. double rocks[3];
  2852. double rock[3];
  2853. rocks[0] = CM_WX_15s[0] - JBottom_WX_15s[0];
  2854. rocks[1] = CM_WX_15s[1] - JBottom_WX_15s[1];
  2855. rocks[2] = CM_WX_15s[2] - JBottom_WX_15s[2];
  2856. double rock_norm = sqrt(rocks[0] * rocks[0] + rocks[1] * rocks[1] + rocks[2] * rocks[2]);
  2857. if (fabs(rock_norm) < 1e-9)
  2858. {
  2859. rock[0] = rock[1] = rock[2] = 0.0;
  2860. }
  2861. else
  2862. {
  2863. rock[0] = rocks[0] / rock_norm;
  2864. rock[1] = rocks[1] / rock_norm;
  2865. rock[2] = rocks[2] / rock_norm;
  2866. }
  2867. double azimuth_deg, elevation_deg, theta;
  2868. azimuth_deg = atan2(rock[1], rock[0]) * 180.0f / PI;
  2869. if (azimuth_deg < 0)
  2870. {
  2871. azimuth_deg += 360.0;
  2872. }
  2873. theta = acos(rock[2]) * 180.0f / PI;
  2874. elevation_deg = 90.0 - theta;
  2875. if (elevation_deg < 0)
  2876. {
  2877. elevation_deg = 0.0;
  2878. }
  2879. *rt_azimuth_deg = azimuth_deg;
  2880. *rt_elevation_deg = elevation_deg;
  2881. char flag_chuanwang = 0;
  2882. double J0_WX_15s[3] = {0.0, 0.0, 0.0};
  2883. //double CM_WX_15s[3] = {CM_WX[0], -CM_WX[2], CM_WX[1]};
  2884. //double JBottom_WX_15s[3] = {JBottom_WX[0], -JBottom_WX[2], JBottom_WX[1]};
  2885. double CM_WX[3] = {CM_WX_15s[0], CM_WX_15s[2], -CM_WX_15s[1]};
  2886. double JBottom_WX[3] = {JBottom_WX_15s[0], JBottom_WX_15s[2], -JBottom_WX_15s[1]};
  2887. if (JBottom_WX_15s[2] < 0)
  2888. {
  2889. flag_chuanwang = 1;
  2890. double J0_WX[3];
  2891. double diff[3] = {
  2892. JBottom_WX[0] - CM_WX[0],
  2893. JBottom_WX[1] - CM_WX[1],
  2894. JBottom_WX[2] - CM_WX[2]};
  2895. double denominator = fabs(JBottom_WX[1]) + CM_WX[1];
  2896. if (fabs(denominator) < 1e-9)
  2897. {
  2898. J0_WX[0] = CM_WX[0];
  2899. J0_WX[1] = CM_WX[1];
  2900. J0_WX[2] = CM_WX[2];
  2901. }
  2902. else
  2903. {
  2904. double scalar = CM_WX[1] / denominator;
  2905. J0_WX[0] = diff[0] * scalar + CM_WX[0];
  2906. J0_WX[1] = diff[1] * scalar + CM_WX[1];
  2907. J0_WX[2] = diff[2] * scalar + CM_WX[2];
  2908. }
  2909. J0_WX_15s[0] = J0_WX[0];
  2910. J0_WX_15s[1] = -J0_WX[2];
  2911. J0_WX_15s[2] = JBottom_WX[1];
  2912. }else
  2913. {
  2914. flag_chuanwang = 0;
  2915. J0_WX_15s[0] = JBottom_WX[0];
  2916. J0_WX_15s[1] = JBottom_WX[1];
  2917. J0_WX_15s[2] = JBottom_WX[2];
  2918. }
  2919. *rt_flag_chuanwang = flag_chuanwang;
  2920. }
  2921. double LidarFusionNode::deg2rad(double deg)
  2922. {
  2923. return deg * PI / 180.0;
  2924. }
  2925. double LidarFusionNode::cosd(double deg)
  2926. {
  2927. return cos(deg2rad(deg));
  2928. }
  2929. double LidarFusionNode::sind(double deg)
  2930. {
  2931. return sin(deg2rad(deg));
  2932. }
  2933. void LidarFusionNode::mat33_mult(const double A[3][3], const double B[3][3], double C[3][3])
  2934. {
  2935. for (int i = 0; i < 3; i++)
  2936. {
  2937. for (int j = 0; j < 3; j++)
  2938. {
  2939. C[i][j] = 0.0;
  2940. for (int k = 0; k < 3; k++)
  2941. {
  2942. C[i][j] += A[i][k] * B[k][j];
  2943. }
  2944. }
  2945. }
  2946. }
  2947. void LidarFusionNode::mat33_transpose(const double A[3][3], double AT[3][3])
  2948. {
  2949. for (int i = 0; i < 3; i++)
  2950. {
  2951. for (int j = 0; j < 3; j++)
  2952. {
  2953. AT[i][j] = A[j][i];
  2954. }
  2955. }
  2956. }
  2957. void LidarFusionNode::mat33_vec3_mult(const double A[3][3], const double a[3], double b[3])
  2958. {
  2959. for (int i = 0; i < 3; i++)
  2960. {
  2961. b[i] = 0.0;
  2962. for (int k = 0; k < 3; k++)
  2963. {
  2964. b[i] += A[i][k] * a[k];
  2965. }
  2966. }
  2967. }
  2968. void LidarFusionNode::vec3_sub(const double a[3], const double b[3], double c[3])
  2969. {
  2970. for (int i = 0; i < 3; i++)
  2971. {
  2972. c[i] = a[i] - b[i];
  2973. }
  2974. }
  2975. void LidarFusionNode::vec3_add(const double a[3], const double b[3], double c[3])
  2976. {
  2977. for (int i = 0; i < 3; i++)
  2978. {
  2979. c[i] = a[i] + b[i];
  2980. }
  2981. }
  2982. void LidarFusionNode::calculate_CM_WX(const double COM_ZL[3], double SheXiang, const double att[3], const double Lever[3], double CM_WX[3])
  2983. {
  2984. // 提取姿态角
  2985. double fuyang = att[0];
  2986. double henggun = att[1];
  2987. double heading = att[2];
  2988. // 定义变换矩阵T = [0 1 0; 0 0 1; 1 0 0]
  2989. double T[3][3] = {
  2990. {0.0, 1.0, 0.0},
  2991. {0.0, 0.0, 1.0},
  2992. {1.0, 0.0, 0.0}};
  2993. double T0[3][3] = {0};
  2994. mat33_transpose(T, T0);
  2995. double temp_COM_ZL[3] = {0};
  2996. double temp_Lever[3] = {0};
  2997. mat33_vec3_mult(T0, COM_ZL, temp_COM_ZL);
  2998. mat33_vec3_mult(T0, Lever, temp_Lever);
  2999. // 1. 计算C_ZL2N矩阵 (箭系转网系)
  3000. double C_ZL2N[3][3] = {0};
  3001. C_ZL2N[0][0] = cosd(SheXiang);
  3002. C_ZL2N[0][1] = sind(SheXiang);
  3003. C_ZL2N[0][2] = 0.0;
  3004. C_ZL2N[1][0] = -sind(SheXiang);
  3005. C_ZL2N[1][1] = cosd(SheXiang);
  3006. C_ZL2N[1][2] = 0.0;
  3007. C_ZL2N[2][0] = 0.0;
  3008. C_ZL2N[2][1] = 0.0;
  3009. C_ZL2N[2][2] = 1.0;
  3010. // 2. 计算各姿态旋转矩阵
  3011. // 偏航角(heading)旋转矩阵 C3_heading
  3012. double C3_heading[3][3] = {0};
  3013. C3_heading[0][0] = cosd(heading);
  3014. C3_heading[0][1] = sind(heading);
  3015. C3_heading[0][2] = 0.0;
  3016. C3_heading[1][0] = -sind(heading);
  3017. C3_heading[1][1] = cosd(heading);
  3018. C3_heading[1][2] = 0.0;
  3019. C3_heading[2][0] = 0.0;
  3020. C3_heading[2][1] = 0.0;
  3021. C3_heading[2][2] = 1.0;
  3022. // 俯仰角(fuyang)旋转矩阵 C1_fuyang (修正原MATLAB代码的笔误O)
  3023. double C1_fuyang[3][3] = {0};
  3024. C1_fuyang[0][0] = 1.0;
  3025. C1_fuyang[0][1] = 0.0;
  3026. C1_fuyang[0][2] = 0.0;
  3027. C1_fuyang[1][0] = 0.0;
  3028. C1_fuyang[1][1] = cosd(fuyang);
  3029. C1_fuyang[1][2] = sind(fuyang);
  3030. C1_fuyang[2][0] = 0.0;
  3031. C1_fuyang[2][1] = -sind(fuyang);
  3032. C1_fuyang[2][2] = cosd(fuyang);
  3033. // 横滚角(henggun)旋转矩阵 C2_henggun (修正原MATLAB代码的fuyang笔误)
  3034. double C2_henggun[3][3] = {0};
  3035. C2_henggun[0][0] = cosd(henggun);
  3036. C2_henggun[0][1] = 0.0;
  3037. C2_henggun[0][2] = -sind(henggun);
  3038. C2_henggun[1][0] = 0.0;
  3039. C2_henggun[1][1] = 1.0;
  3040. C2_henggun[1][2] = 0.0;
  3041. C2_henggun[2][0] = sind(henggun); // 原MATLAB代码此处写错为fuyang,已修正
  3042. C2_henggun[2][1] = 0.0;
  3043. C2_henggun[2][2] = cosd(henggun);
  3044. // 计算C_N2WX = C2_henggun * C1_fuyang * C3_heading
  3045. double C1C3[3][3] = {0};
  3046. mat33_mult(C1_fuyang, C3_heading, C1C3);
  3047. double C_N2WX[3][3] = {0};
  3048. mat33_mult(C2_henggun, C1C3, C_N2WX);
  3049. // 计算C_ZL2WX = C_N2WX * C_ZL2N
  3050. double C_ZL2WX[3][3] = {0};
  3051. mat33_mult(C_N2WX, C_ZL2N, C_ZL2WX);
  3052. // 计算C_WX02WX = C2_henggun * C1_fuyang
  3053. double C_WX02WX[3][3] = {0};
  3054. mat33_mult(C2_henggun, C1_fuyang, C_WX02WX);
  3055. // 计算C_WX2WX0 = C_WX02WX的转置
  3056. double C_WX2WX0[3][3] = {0};
  3057. mat33_transpose(C_WX02WX, C_WX2WX0);
  3058. // 计算C_WX2WX0 * Lever
  3059. double temp_vec1[3] = {0};
  3060. mat33_vec3_mult(C_WX2WX0, temp_Lever, temp_vec1);
  3061. // 计算(C_WX2WX0*Lever - Lever)
  3062. double temp_vec2[3] = {0};
  3063. vec3_sub(temp_vec1, temp_Lever, temp_vec2);
  3064. // 计算CCO_WX = C_WX02WX * temp_vec2
  3065. double CCO_WX[3] = {0};
  3066. mat33_vec3_mult(C_WX02WX, temp_vec2, CCO_WX);
  3067. // 计算C_ZL2WX * COM_ZL
  3068. double temp_vec3[3] = {0};
  3069. mat33_vec3_mult(C_ZL2WX, temp_COM_ZL, temp_vec3);
  3070. // 计算C_ZL2WX*COM_ZL + CCO_WX
  3071. double temp_vec4[3] = {0};
  3072. vec3_add(temp_vec3, CCO_WX, temp_vec4);
  3073. // 最终计算CM_WX = T * temp_vec4
  3074. mat33_vec3_mult(T, temp_vec4, CM_WX);
  3075. }
  3076. void LidarFusionNode::calculate_ZL_WX(const double COM_ZL_processed[3], const double COM_att[3], const double JBottom2JM_JT[3], double JBottom_ZL[3])
  3077. {
  3078. // 提取姿态角
  3079. double fuyang = COM_att[0];
  3080. double henggun = COM_att[1];
  3081. double heading = COM_att[2];
  3082. double C_J3[3][3] = {0};
  3083. C_J3[0][0] = cosd(fuyang);
  3084. C_J3[0][1] = sind(fuyang);
  3085. C_J3[0][2] = 0.0;
  3086. C_J3[1][0] = -sind(fuyang);
  3087. C_J3[1][1] = cosd(fuyang);
  3088. C_J3[1][2] = 0.0;
  3089. C_J3[2][0] = 0.0;
  3090. C_J3[2][1] = 0.0;
  3091. C_J3[2][2] = 1.0;
  3092. double C_J2[3][3] = {0};
  3093. C_J2[0][0] = cosd(henggun);
  3094. C_J2[0][1] = 0.0;
  3095. C_J2[0][2] = -sind(henggun);
  3096. C_J2[1][0] = 0.0;
  3097. C_J2[1][1] = 1.0;
  3098. C_J2[1][2] = 0.0;
  3099. C_J2[2][0] = sind(henggun);
  3100. C_J2[2][1] = 0.0;
  3101. C_J2[2][2] = cosd(henggun);
  3102. double C_J1[3][3] = {0};
  3103. C_J1[0][0] = 1.0;
  3104. C_J1[0][1] = 0.0;
  3105. C_J1[0][2] = 0.0;
  3106. C_J1[1][0] = 0.0;
  3107. C_J1[1][1] = cosd(heading);
  3108. C_J1[1][2] = sind(heading);
  3109. C_J1[2][0] = 0.0;
  3110. C_J1[2][1] = -sind(heading);
  3111. C_J1[2][2] = cosd(heading);
  3112. double C_ZL2JT_temp[3][3] = {0};
  3113. mat33_mult(C_J2, C_J3, C_ZL2JT_temp);
  3114. double C_ZL2JT[3][3] = {0};
  3115. mat33_mult(C_J1, C_ZL2JT_temp, C_ZL2JT);
  3116. double C_ZL2JT0[3][3] = {0};
  3117. mat33_transpose(C_ZL2JT, C_ZL2JT0);
  3118. double JBottom2JM_ZL_temp[3] = {0};
  3119. mat33_vec3_mult(C_ZL2JT0, JBottom2JM_JT, JBottom2JM_ZL_temp);
  3120. vec3_sub(COM_ZL_processed, JBottom2JM_ZL_temp, JBottom_ZL);
  3121. }
  3122. // 姿态角转旋转矩阵 Cnb(载体->导航)
  3123. void LidarFusionNode::a2cnb(const double att[3], double Cnb[3][3])
  3124. {
  3125. double si = sin(att[0]);
  3126. double ci = cos(att[0]);
  3127. double sj = sin(att[1]);
  3128. double cj = cos(att[1]);
  3129. double sk = sin(att[2]);
  3130. double ck = cos(att[2]);
  3131. Cnb[0][0] = cj * ck - si * sj * sk;
  3132. Cnb[0][1] = -ci * sk;
  3133. Cnb[0][2] = sj * ck + si * cj * sk;
  3134. Cnb[1][0] = cj * sk + si * sj * ck;
  3135. Cnb[1][1] = ci * ck;
  3136. Cnb[1][2] = sj * sk - si * cj * ck;
  3137. Cnb[2][0] = -ci * sj;
  3138. Cnb[2][1] = si;
  3139. Cnb[2][2] = ci * cj;
  3140. }
  3141. // 3x3矩阵转置
  3142. void LidarFusionNode::mat3_transpose(const double m[3][3], double res[3][3])
  3143. {
  3144. for (int i = 0; i < 3; i++) {
  3145. for (int j = 0; j < 3; j++) {
  3146. res[i][j] = m[j][i];
  3147. }
  3148. }
  3149. }
  3150. // 3x3矩阵乘法:a * b
  3151. void LidarFusionNode::mat3_mult(const double a[3][3], const double b[3][3], double res[3][3])
  3152. {
  3153. double tmp[3][3] = {0};
  3154. for (int i = 0; i < 3; i++) {
  3155. for (int j = 0; j < 3; j++) {
  3156. tmp[i][j] = a[i][0] * b[0][j] + a[i][1] * b[1][j] + a[i][2] * b[2][j];
  3157. }
  3158. }
  3159. memcpy(res, tmp, sizeof(tmp));
  3160. }
  3161. // 3x3矩阵 * 3x1向量
  3162. void LidarFusionNode::mat3_vec_mult(const double m[3][3], const double v[3], double res[3])
  3163. {
  3164. res[0] = m[0][0] * v[0] + m[0][1] * v[1] + m[0][2] * v[2];
  3165. res[1] = m[1][0] * v[0] + m[1][1] * v[1] + m[1][2] * v[2];
  3166. res[2] = m[2][0] * v[0] + m[2][1] * v[1] + m[2][2] * v[2];
  3167. }
  3168. //======================== 函数1:挂钩L坐标 → 箭底N / 挂钩N ========================
  3169. // 输入:pos_hook[3], att_hook[3], att_net[3]
  3170. // 输出:pos_bottom_N[3], pos_hook_N[3]
  3171. void LidarFusionNode::poshookL2posbottomN(
  3172. const double pos_hook[3],
  3173. const double att_hook[3],
  3174. const double att_net[3],
  3175. double pos_bottom_N[3],
  3176. double pos_hook_N[3])
  3177. {
  3178. const double glv_deg = M_PI / 180.0;
  3179. const double dir = 130.0 * glv_deg;
  3180. const double yaw_0 = att_net[2];
  3181. double lever_os[3] = {0.36, -(65.2 - 3.56), 0.0};
  3182. double lever_hook[3] = {32.498, 0.0, 0.0};
  3183. // 坐标系变换
  3184. const double c_rfu_fur[3][3] = {{0,0,1}, {1,0,0}, {0,1,0}};
  3185. double c_fur_rfu[3][3];
  3186. mat3_transpose(c_rfu_fur, c_fur_rfu);
  3187. double lever_os_t[3], lever_hook_t[3], pos_hook_t[3];
  3188. mat3_vec_mult(c_rfu_fur, lever_os, lever_os_t);
  3189. mat3_vec_mult(c_rfu_fur, lever_hook, lever_hook_t);
  3190. mat3_vec_mult(c_rfu_fur, pos_hook, pos_hook_t);
  3191. // 计算 cLR
  3192. double att1[3] = {att_hook[0], 0, 0};
  3193. double att2[3] = {0, 0, att_hook[1]};
  3194. double att3[3] = {0, att_hook[2], 0};
  3195. double m1[3][3], m2[3][3], m3[3][3], tmp[3][3], cLR[3][3];
  3196. a2cnb(att1, m1); a2cnb(att2, m2); a2cnb(att3, m3);
  3197. mat3_mult(m1, m2, tmp);
  3198. mat3_mult(tmp, m3, cLR);
  3199. // cGL / cLG
  3200. double attGL[3] = {0, 0, -dir};
  3201. double cGL[3][3], cLG[3][3];
  3202. a2cnb(attGL, cGL);
  3203. mat3_transpose(cGL, cLG);
  3204. // cGN
  3205. double cGN[3][3];
  3206. a2cnb(att_net, cGN);
  3207. // cNL
  3208. double cGN_T[3][3], cNL[3][3];
  3209. mat3_transpose(cGN, cGN_T);
  3210. mat3_mult(cGN_T, cGL, cNL);
  3211. // cGA / cAG
  3212. double attGA[3] = {0, 0, yaw_0};
  3213. double cGA[3][3], cAG[3][3];
  3214. a2cnb(attGA, cGA);
  3215. mat3_transpose(cGA, cAG);
  3216. // cAN / cLA
  3217. double cAN[3][3], cLA[3][3];
  3218. mat3_mult(cAG, cGN, cAN);
  3219. mat3_mult(cLG, cGA, cLA);
  3220. // pos_bottom
  3221. double cLR_lev[3], pos_bottom[3];
  3222. mat3_vec_mult(cLR, lever_hook_t, cLR_lev);
  3223. vec3_sub(pos_hook_t, cLR_lev, pos_bottom);
  3224. // 公共项
  3225. double cAN_lev[3], temp[3], cLA_temp[3];
  3226. mat3_vec_mult(cAN, lever_os_t, cAN_lev);
  3227. vec3_sub(cAN_lev, lever_os_t, temp);
  3228. mat3_vec_mult(cLA, temp, cLA_temp);
  3229. // 计算输出
  3230. double vec1[3], vec2[3];
  3231. vec3_add(pos_bottom, cLA_temp, vec1);
  3232. vec3_add(pos_hook_t, cLA_temp, vec2);
  3233. mat3_vec_mult(cNL, vec1, pos_bottom_N);
  3234. mat3_vec_mult(cNL, vec2, pos_hook_N);
  3235. // 最终坐标转换
  3236. double tmp1[3], tmp2[3];
  3237. mat3_vec_mult(c_fur_rfu, pos_bottom_N, pos_bottom_N);
  3238. mat3_vec_mult(c_fur_rfu, pos_hook_N, pos_hook_N);
  3239. }
  3240. //======================== 函数2:箭底N坐标 → 挂钩L坐标 ========================
  3241. // 输入:pos_bottom_N[3], att_hook[3], att_net[3]
  3242. // 输出:pos_hook[3]
  3243. void LidarFusionNode::posbottomN2poshookL(
  3244. const double pos_bottom_N[3],
  3245. const double att_hook[3],
  3246. const double att_net[3],
  3247. double pos_hook[3])
  3248. {
  3249. const double glv_deg = M_PI / 180.0;
  3250. const double dir = 130.0 * glv_deg;
  3251. const double yaw_0 = att_net[2];
  3252. double lever_os[3] = {0.36, -(65.2 - 3.56), 0.0};
  3253. double lever_hook[3] = {32.498, 0.0, 0.0};
  3254. // 坐标系变换
  3255. const double c_rfu_fur[3][3] = {{0,0,1}, {1,0,0}, {0,1,0}};
  3256. double c_fur_rfu[3][3];
  3257. mat3_transpose(c_rfu_fur, c_fur_rfu);
  3258. double lever_os_t[3], lever_hook_t[3], pos_N_t[3];
  3259. mat3_vec_mult(c_rfu_fur, lever_os, lever_os_t);
  3260. mat3_vec_mult(c_rfu_fur, lever_hook, lever_hook_t);
  3261. mat3_vec_mult(c_rfu_fur, pos_bottom_N, pos_N_t);
  3262. double att1[3] = {att_hook[0], 0, 0};
  3263. double att2[3] = {0, 0, att_hook[1]};
  3264. double att3[3] = {0, att_hook[2], 0};
  3265. double m1[3][3], m2[3][3], m3[3][3], tmp[3][3], cLR[3][3];
  3266. a2cnb(att1, m1);
  3267. a2cnb(att2, m2);
  3268. a2cnb(att3, m3);
  3269. mat3_mult(m1, m2, tmp);
  3270. mat3_mult(tmp, m3, cLR);
  3271. double attGL[3] = {0, 0, -dir};
  3272. double cGL[3][3];
  3273. a2cnb(attGL, cGL);
  3274. double cGN[3][3];
  3275. a2cnb(att_net, cGN);
  3276. double cGN_T[3][3], cNL[3][3], cLN[3][3];
  3277. mat3_transpose(cGN, cGN_T);
  3278. mat3_mult(cGN_T, cGL, cNL);
  3279. mat3_transpose(cNL, cLN);
  3280. double attGA[3] = {0, 0, yaw_0};
  3281. double cGA[3][3], cAG[3][3];
  3282. a2cnb(attGA, cGA);
  3283. mat3_transpose(cGA, cAG);
  3284. double cAN[3][3], cNA[3][3];
  3285. mat3_mult(cAG, cGN, cAN);
  3286. mat3_transpose(cAN, cNA);
  3287. double cNA_lev[3], tmp_sub[3], tmp_vec[3], pos_bottom[3];
  3288. mat3_vec_mult(cNA, lever_os_t, cNA_lev);
  3289. vec3_sub(lever_os_t, cNA_lev, tmp_sub);
  3290. vec3_sub(pos_N_t, tmp_sub, tmp_vec);
  3291. mat3_vec_mult(cLN, tmp_vec, pos_bottom);
  3292. // pos_hook
  3293. double cLR_lev[3], pos_hook_mid[3];
  3294. mat3_vec_mult(cLR, lever_hook_t, cLR_lev);
  3295. vec3_add(pos_bottom, cLR_lev, pos_hook_mid);
  3296. // 最终坐标转换
  3297. mat3_vec_mult(c_fur_rfu, pos_hook_mid, pos_hook);
  3298. }