[{"data":1,"prerenderedAt":5328},["ShallowReactive",2],{"wiki-page-/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-1-li-cheng-ji-odom":3,"wiki-doc-items-/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-1-li-cheng-ji-odom":4967,"language-switcher-data-/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-1-li-cheng-ji-odom":5312,"wiki-i18n-paths-/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-1-li-cheng-ji-odom":5327},{"id":4,"title":5,"body":6,"canonicalPath":4948,"chapter":4949,"chapterSort":4950,"date":4951,"description":26,"docI18nKey":4952,"docKey":4953,"docRoot":4954,"docTitle":4955,"extension":4956,"i18nKey":4957,"isBlogPost":4958,"isWikiDoc":667,"isWikiIndex":4958,"layout":4959,"legacyPath":4959,"locale":4960,"localeSlug":4961,"meta":4962,"navigation":667,"path":4948,"seo":4963,"sourcePath":4964,"sourceStem":4957,"stem":4965,"wikiDepth":34,"__hash__":4966},"content/_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-1-里程计Odom.md","里程計Odom",{"type":7,"value":8,"toc":4943},"minimark",[9,13,17,20,77,80,99,102,113,116,136,165,175,198,203,246,538,541,577,580,587,593,598,603,608,614,617,620,625,628,1317,1320,4931,4936,4939],[10,11,12],"h3",{"id":12},"功能包創建",[14,15,16],"p",{},"不一定非得要碼盤(里程計Odom)的數據，只要把機器人6個自由度DOF，可以由電機編碼器計算而來（x,y,z,yaw,pitch,roll不懂的看上方Moveit2裏的教學）全部發過來就行。",[14,18,19],{},"首先先創建功能包",[21,22,27],"pre",{"className":23,"code":24,"language":25,"meta":26,"style":26},"language-bash shiki shiki-themes github-light github-dark","ros2 pkg create odom_plumb --build-type ament_cmake --dependencies rclcpp nav_msgs geometry_msgs tf2_ros --node-name odom_node\n","bash","",[28,29,30],"code",{"__ignoreMap":26},[31,32,35,39,43,46,49,53,56,59,62,65,68,71,74],"span",{"class":33,"line":34},"line",1,[31,36,38],{"class":37},"sScJk","ros2",[31,40,42],{"class":41},"sZZnC"," pkg",[31,44,45],{"class":41}," create",[31,47,48],{"class":41}," odom_plumb",[31,50,52],{"class":51},"sj4cs"," --build-type",[31,54,55],{"class":41}," ament_cmake",[31,57,58],{"class":51}," --dependencies",[31,60,61],{"class":41}," rclcpp",[31,63,64],{"class":41}," nav_msgs",[31,66,67],{"class":41}," geometry_msgs",[31,69,70],{"class":41}," tf2_ros",[31,72,73],{"class":51}," --node-name",[31,75,76],{"class":41}," odom_node\n",[14,78,79],{},"先編譯一下",[21,81,83],{"className":23,"code":82,"language":25,"meta":26,"style":26},"colcon build --cmake-args -DCMAKE_EXPORT_COMPILE_COMMANDS=ON\n",[28,84,85],{"__ignoreMap":26},[31,86,87,90,93,96],{"class":33,"line":34},[31,88,89],{"class":37},"colcon",[31,91,92],{"class":41}," build",[31,94,95],{"class":51}," --cmake-args",[31,97,98],{"class":51}," -DCMAKE_EXPORT_COMPILE_COMMANDS=ON\n",[10,100,101],{"id":101},"消息接口",[14,103,104,105,108,109,112],{},"底盤驅動啓動之後，會持續廣播一個比較重要的數據——里程計。里程計用於描述當前機器人相對於出發點的位姿以及速度等信息，里程計在機器人定位和導航的局部路徑規劃中有着重要的作用。在ROS2中里程計消息被封裝爲了",[28,106,107],{},"nav_msgs/msg/Odometry","接口，可通過指令",[28,110,111],{},"ros2 interface show nav_msgs/msg/Odometry","查看該接口的具體數據結構，結果如下：",[14,114,115],{},"它描述的是機器人位姿與速度的預估信息。 其中位姿信息是以header中的frame_id爲參考系的，而速度信息則是以child_frame_id爲參考系的。",[14,117,118,119,123,124,127,128,131,132,135],{},"在 ",[120,121,122],"strong",{},"ROS2"," 中， ",[120,125,126],{},"odom 座標系"," （通常是 ",[28,129,130],{},"odom"," frame）遵循 ",[120,133,134],{},"右手座標系"," ，其定義如下：",[137,138,139,149,157],"ul",{},[140,141,142,145,146],"li",{},[120,143,144],{},"X 軸"," ：向前（前進方向）爲 ",[120,147,148],{},"正",[140,150,151,154,155],{},[120,152,153],{},"Y 軸"," ：向左（左側方向）爲 ",[120,156,148],{},[140,158,159,162,163],{},[120,160,161],{},"Z 軸"," ：向上（垂直地面）爲 ",[120,164,148],{},[14,166,118,167,170,171,174],{},[120,168,169],{},"ROS2 的 odom 座標系"," （右手座標系）中， ",[120,172,173],{},"yaw 角的定義"," 如下：",[137,176,177,187,193],{},[140,178,179,182,183,186],{},[120,180,181],{},"yaw = 0"," ：機器人面向 ",[120,184,185],{},"X 軸正方向"," （向前）。",[140,188,189,192],{},[120,190,191],{},"逆時針（CCW，Counter Clockwise）旋轉爲正"," 。",[140,194,195,192],{},[120,196,197],{},"順時針（CW，Clockwise）旋轉爲負",[14,199,200],{},[120,201,202],{},"yaw 角範圍",[137,204,205,222,237],{},[140,206,207,210,211],{},[28,208,209],{},"yaw ∈ (-π, π]"," ",[120,212,213,214,217,218,221],{},"（即 ",[28,215,216],{},"-180°"," 到 ",[28,219,220],{},"180°","）",[140,223,224,225,228,229,232,233,236],{},"當 ",[28,226,227],{},"yaw = π","（180°），如果繼續增加，應該跳轉到 ",[28,230,231],{},"-π","（-180°），而不是 ",[28,234,235],{},"π","。",[140,238,224,239,242,243,245],{},[28,240,241],{},"yaw = -π","（-180°），如果繼續減少，應該跳轉到 ",[28,244,235],{},"（180°）。",[21,247,249],{"className":23,"code":248,"language":25,"meta":26,"style":26},"std_msgs/Header header # 标头\n    builtin_interfaces/Time stamp # 时间戳\n        int32 sec\n        uint32 nanosec\n    string frame_id # 位姿信息所参考的坐标系\n位姿信息所指向的坐标系，也是速度信息所参考的坐标系\nstring child_frame_id\n相对于frame_id的预估位姿信息\ngeometry_msgs/PoseWithCovariance pose\n    Pose pose\n        Point position # 坐标\n            float64 x\n            float64 y\n            float64 z\n        Quaternion orientation # 四元数\n            float64 x 0\n            float64 y 0\n            float64 z 0\n            float64 w 1\n    float64[36] covariance\n相对于child_frame_id的预估线速度与角速度\ngeometry_msgs/TwistWithCovariance twist\n    Twist twist\n        Vector3  linear # 线速度\n            float64 x\n            float64 y\n            float64 z\n        Vector3  angular # 角速度\n            float64 x\n            float64 y\n            float64 z\n    float64[36] covariance\n",[28,250,251,263,275,284,293,305,311,320,326,335,343,355,364,372,380,392,403,413,423,434,443,449,458,466,478,485,492,499,510,517,524,531],{"__ignoreMap":26},[31,252,253,256,259],{"class":33,"line":34},[31,254,255],{"class":37},"std_msgs/Header",[31,257,258],{"class":41}," header",[31,260,262],{"class":261},"sJ8bj"," # 标头\n",[31,264,266,269,272],{"class":33,"line":265},2,[31,267,268],{"class":37},"    builtin_interfaces/Time",[31,270,271],{"class":41}," stamp",[31,273,274],{"class":261}," # 时间戳\n",[31,276,278,281],{"class":33,"line":277},3,[31,279,280],{"class":37},"        int32",[31,282,283],{"class":41}," sec\n",[31,285,287,290],{"class":33,"line":286},4,[31,288,289],{"class":37},"        uint32",[31,291,292],{"class":41}," nanosec\n",[31,294,296,299,302],{"class":33,"line":295},5,[31,297,298],{"class":37},"    string",[31,300,301],{"class":41}," frame_id",[31,303,304],{"class":261}," # 位姿信息所参考的坐标系\n",[31,306,308],{"class":33,"line":307},6,[31,309,310],{"class":37},"位姿信息所指向的坐标系，也是速度信息所参考的坐标系\n",[31,312,314,317],{"class":33,"line":313},7,[31,315,316],{"class":37},"string",[31,318,319],{"class":41}," child_frame_id\n",[31,321,323],{"class":33,"line":322},8,[31,324,325],{"class":37},"相对于frame_id的预估位姿信息\n",[31,327,329,332],{"class":33,"line":328},9,[31,330,331],{"class":37},"geometry_msgs/PoseWithCovariance",[31,333,334],{"class":41}," pose\n",[31,336,338,341],{"class":33,"line":337},10,[31,339,340],{"class":37},"    Pose",[31,342,334],{"class":41},[31,344,346,349,352],{"class":33,"line":345},11,[31,347,348],{"class":37},"        Point",[31,350,351],{"class":41}," position",[31,353,354],{"class":261}," # 坐标\n",[31,356,358,361],{"class":33,"line":357},12,[31,359,360],{"class":37},"            float64",[31,362,363],{"class":41}," x\n",[31,365,367,369],{"class":33,"line":366},13,[31,368,360],{"class":37},[31,370,371],{"class":41}," y\n",[31,373,375,377],{"class":33,"line":374},14,[31,376,360],{"class":37},[31,378,379],{"class":41}," z\n",[31,381,383,386,389],{"class":33,"line":382},15,[31,384,385],{"class":37},"        Quaternion",[31,387,388],{"class":41}," orientation",[31,390,391],{"class":261}," # 四元数\n",[31,393,395,397,400],{"class":33,"line":394},16,[31,396,360],{"class":37},[31,398,399],{"class":41}," x",[31,401,402],{"class":51}," 0\n",[31,404,406,408,411],{"class":33,"line":405},17,[31,407,360],{"class":37},[31,409,410],{"class":41}," y",[31,412,402],{"class":51},[31,414,416,418,421],{"class":33,"line":415},18,[31,417,360],{"class":37},[31,419,420],{"class":41}," z",[31,422,402],{"class":51},[31,424,426,428,431],{"class":33,"line":425},19,[31,427,360],{"class":37},[31,429,430],{"class":41}," w",[31,432,433],{"class":51}," 1\n",[31,435,437,440],{"class":33,"line":436},20,[31,438,439],{"class":37},"    float64[36]",[31,441,442],{"class":41}," covariance\n",[31,444,446],{"class":33,"line":445},21,[31,447,448],{"class":37},"相对于child_frame_id的预估线速度与角速度\n",[31,450,452,455],{"class":33,"line":451},22,[31,453,454],{"class":37},"geometry_msgs/TwistWithCovariance",[31,456,457],{"class":41}," twist\n",[31,459,461,464],{"class":33,"line":460},23,[31,462,463],{"class":37},"    Twist",[31,465,457],{"class":41},[31,467,469,472,475],{"class":33,"line":468},24,[31,470,471],{"class":37},"        Vector3",[31,473,474],{"class":41},"  linear",[31,476,477],{"class":261}," # 线速度\n",[31,479,481,483],{"class":33,"line":480},25,[31,482,360],{"class":37},[31,484,363],{"class":41},[31,486,488,490],{"class":33,"line":487},26,[31,489,360],{"class":37},[31,491,371],{"class":41},[31,493,495,497],{"class":33,"line":494},27,[31,496,360],{"class":37},[31,498,379],{"class":41},[31,500,502,504,507],{"class":33,"line":501},28,[31,503,471],{"class":37},[31,505,506],{"class":41},"  angular",[31,508,509],{"class":261}," # 角速度\n",[31,511,513,515],{"class":33,"line":512},29,[31,514,360],{"class":37},[31,516,363],{"class":41},[31,518,520,522],{"class":33,"line":519},30,[31,521,360],{"class":37},[31,523,371],{"class":41},[31,525,527,529],{"class":33,"line":526},31,[31,528,360],{"class":37},[31,530,379],{"class":41},[31,532,534,536],{"class":33,"line":533},32,[31,535,439],{"class":37},[31,537,442],{"class":41},[14,539,540],{},"需要注意的是，",[542,543,544,551,561,574],"ol",{},[140,545,546,547,550],{},"座標和位姿是相對於",[120,548,549],{},"frame_id","的，一般是odom自己。",[140,552,553,554,557,558,560],{},"而線速度和角速度是相對於",[120,555,556],{},"child_frame_id","的。一般是base_link ",[120,559,236],{}," （這裏注意，學長我最初就弄錯了）",[140,562,563,564,567,568,571,572,236],{},"雖然Twist是相對於child_frame_id ",[120,565,566],{},"（"," base_link）的，但是他表達的是",[120,569,570],{},"瞬時值","，就和汽車一樣，汽車上面的速度表也是相對於車身的",[120,573,570],{},[140,575,576],{},"里程計在計算時是存在累計誤差的，它所描述的是機器人的預估位姿，並不絕對準確。",[10,578,579],{"id":579},"節點主要邏輯",[14,581,582,583,586],{},"所以我們需要初始化",[28,584,585],{},"nav_msgs::msg::Odometry","併發布出去。",[14,588,589],{},[590,591],"img",{"alt":26,"src":592},"https://cdn.tungchiahui.cn/tungwebsite/assets/images/2023/12/30/image1794.webp",[14,594,595],{},[590,596],{"alt":26,"src":597},"https://cdn.tungchiahui.cn/tungwebsite/assets/images/2023/12/30/image1795.webp",[14,599,600],{},[590,601],{"alt":26,"src":602},"https://cdn.tungchiahui.cn/tungwebsite/assets/images/2023/12/30/image1796.webp",[14,604,605],{},[590,606],{"alt":26,"src":607},"https://cdn.tungchiahui.cn/tungwebsite/assets/images/2023/12/30/image1797.webp",[14,609,610,611,613],{},"所以你需要從MCU單片機上去獲取這些數據，或者計算這些數據，並以",[28,612,585],{},"類型的消息發送出去。",[14,615,616],{},"注意，如果你沒有正兒八經的里程計，那麼里程計的數據可以由底盤電機編碼器數據計算而成。",[14,618,619],{},"除了發佈話題的代碼，別忘記發佈odom與base_link之間的動態座標變換。",[14,621,622],{},[590,623],{"alt":26,"src":624},"https://cdn.tungchiahui.cn/tungwebsite/assets/images/2023/12/30/image1798.webp",[14,626,627],{},"下方是運動學正解算出來的odom數據:",[21,629,633],{"className":630,"code":631,"language":632,"meta":26,"style":26},"language-cpp shiki shiki-themes github-light github-dark","#include \"odom_mg513.h\"\n#include \"mg513_gmr500ppr.h\"\n//#include \u003Ccmath>\n#include \"arm_math.h\"\n\nODOM_Motor odom_motor_;\n\n// 坐标系满足右手坐标系\n\n//（单位：米）\n//轮距\nextern fp32 Wheel_Spacing;\n//轴距\nextern fp32 Alex_Spacing;\n//轮子半径\nextern fp32 Wheel_Radius;\n\nvoid ODOM_Motor::Analysis(fp32 dt)\n{\n  this->dt = dt;\n  for(int16_t i = 0;i \u003C 4;i++)\n    {\n        // 将 RPM 转换为 m/s\n      encoder_wheel_velocities_[i] = mg513_gmr500ppr_motor[i].encoder.motor_data.motor_speed  * 2.0f * 3.14159265358979f * Wheel_Radius / 60.0f;\n    }\n    // 计算机器人前进的线速度和角速度，公式不需要轮半径\n    //线速度，四个轮子在机器人的运动学模型中贡献相同，所以要除以4\n    this->vx = ( encoder_wheel_velocities_[0] + encoder_wheel_velocities_[1] - encoder_wheel_velocities_[2] - encoder_wheel_velocities_[3]) / 4.0f;\n    this->vy = ( encoder_wheel_velocities_[0] - encoder_wheel_velocities_[1] - encoder_wheel_velocities_[2] + encoder_wheel_velocities_[3]) / 4.0f;\n\n    //线速度，轮距（wheel_spacing） 决定了左右轮对旋转的贡献程度，轴距（alex_spacing） 决定了前后轮对旋转的贡献程度，\n    //所以要除以底盘尺寸，alex_spacing + wheel_spacing 是底盘尺寸。\n    this->vw = (-encoder_wheel_velocities_[0] - encoder_wheel_velocities_[1] - encoder_wheel_velocities_[2] - encoder_wheel_velocities_[3]) / (4.0f * (Wheel_Spacing + Alex_Spacing));\n\n    // 更新机器人的位置（假设机器人沿着y轴移动）\n//     this->x_position += this->vx * std::__math::cos(this->yaw) * this->dt;  \n//     this->y_position += this->vy * std::__math::sin(this->yaw) * this->dt;\n    this->x_position += this->vx * arm_cos_f32(this->yaw) * this->dt;  \n    this->y_position += this->vy * arm_sin_f32(this->yaw) * this->dt;\n    this->yaw += this->vw * this->dt;\n\n    // 保证 yaw 始终在 -PI 到 PI 之间\n    if(this->yaw > 3.14159265358979f) \n    {\n      this->yaw -= 2.0 * 3.14159265358979f;\n    }\n    if(this->yaw \u003C -3.14159265358979f) \n    {\n      this->yaw += 2.0 * 3.14159265358979f;\n    }\n\n//    this->yaw_deg = this->yaw *  180.0f / 3.14159265358979f;\n\n}\n\n","cpp",[28,634,635,644,651,656,663,669,675,679,684,688,693,698,706,711,718,723,730,734,761,766,780,815,820,825,868,873,878,883,942,989,993,998,1003,1068,1073,1079,1085,1091,1127,1159,1179,1184,1190,1212,1217,1238,1243,1266,1271,1290,1295,1300,1306,1311],{"__ignoreMap":26},[31,636,637,641],{"class":33,"line":34},[31,638,640],{"class":639},"szBVR","#include",[31,642,643],{"class":41}," \"odom_mg513.h\"\n",[31,645,646,648],{"class":33,"line":265},[31,647,640],{"class":639},[31,649,650],{"class":41}," \"mg513_gmr500ppr.h\"\n",[31,652,653],{"class":33,"line":277},[31,654,655],{"class":261},"//#include \u003Ccmath>\n",[31,657,658,660],{"class":33,"line":286},[31,659,640],{"class":639},[31,661,662],{"class":41}," \"arm_math.h\"\n",[31,664,665],{"class":33,"line":295},[31,666,668],{"emptyLinePlaceholder":667},true,"\n",[31,670,671],{"class":33,"line":307},[31,672,674],{"class":673},"sVt8B","ODOM_Motor odom_motor_;\n",[31,676,677],{"class":33,"line":313},[31,678,668],{"emptyLinePlaceholder":667},[31,680,681],{"class":33,"line":322},[31,682,683],{"class":261},"// 坐标系满足右手坐标系\n",[31,685,686],{"class":33,"line":328},[31,687,668],{"emptyLinePlaceholder":667},[31,689,690],{"class":33,"line":337},[31,691,692],{"class":261},"//（单位：米）\n",[31,694,695],{"class":33,"line":345},[31,696,697],{"class":261},"//轮距\n",[31,699,700,703],{"class":33,"line":357},[31,701,702],{"class":639},"extern",[31,704,705],{"class":673}," fp32 Wheel_Spacing;\n",[31,707,708],{"class":33,"line":366},[31,709,710],{"class":261},"//轴距\n",[31,712,713,715],{"class":33,"line":374},[31,714,702],{"class":639},[31,716,717],{"class":673}," fp32 Alex_Spacing;\n",[31,719,720],{"class":33,"line":382},[31,721,722],{"class":261},"//轮子半径\n",[31,724,725,727],{"class":33,"line":394},[31,726,702],{"class":639},[31,728,729],{"class":673}," fp32 Wheel_Radius;\n",[31,731,732],{"class":33,"line":405},[31,733,668],{"emptyLinePlaceholder":667},[31,735,736,739,742,745,748,751,754,758],{"class":33,"line":415},[31,737,738],{"class":639},"void",[31,740,741],{"class":37}," ODOM_Motor",[31,743,744],{"class":673},"::",[31,746,747],{"class":37},"Analysis",[31,749,750],{"class":673},"(",[31,752,753],{"class":37},"fp32",[31,755,757],{"class":756},"s4XuR"," dt",[31,759,760],{"class":673},")\n",[31,762,763],{"class":33,"line":425},[31,764,765],{"class":673},"{\n",[31,767,768,771,774,777],{"class":33,"line":436},[31,769,770],{"class":51},"  this",[31,772,773],{"class":673},"->dt ",[31,775,776],{"class":639},"=",[31,778,779],{"class":673}," dt;\n",[31,781,782,785,787,790,793,795,798,801,804,807,810,813],{"class":33,"line":445},[31,783,784],{"class":639},"  for",[31,786,750],{"class":673},[31,788,789],{"class":639},"int16_t",[31,791,792],{"class":673}," i ",[31,794,776],{"class":639},[31,796,797],{"class":51}," 0",[31,799,800],{"class":673},";i ",[31,802,803],{"class":639},"\u003C",[31,805,806],{"class":51}," 4",[31,808,809],{"class":673},";i",[31,811,812],{"class":639},"++",[31,814,760],{"class":673},[31,816,817],{"class":33,"line":451},[31,818,819],{"class":673},"    {\n",[31,821,822],{"class":33,"line":460},[31,823,824],{"class":261},"        // 将 RPM 转换为 m/s\n",[31,826,827,830,832,835,838,841,844,847,850,852,854,857,860,863,865],{"class":33,"line":468},[31,828,829],{"class":673},"      encoder_wheel_velocities_[i] ",[31,831,776],{"class":639},[31,833,834],{"class":673}," mg513_gmr500ppr_motor[i].encoder.motor_data.motor_speed  ",[31,836,837],{"class":639},"*",[31,839,840],{"class":51}," 2.0",[31,842,843],{"class":639},"f",[31,845,846],{"class":639}," *",[31,848,849],{"class":51}," 3.14159265358979",[31,851,843],{"class":639},[31,853,846],{"class":639},[31,855,856],{"class":673}," Wheel_Radius ",[31,858,859],{"class":639},"/",[31,861,862],{"class":51}," 60.0",[31,864,843],{"class":639},[31,866,867],{"class":673},";\n",[31,869,870],{"class":33,"line":480},[31,871,872],{"class":673},"    }\n",[31,874,875],{"class":33,"line":487},[31,876,877],{"class":261},"    // 计算机器人前进的线速度和角速度，公式不需要轮半径\n",[31,879,880],{"class":33,"line":494},[31,881,882],{"class":261},"    //线速度，四个轮子在机器人的运动学模型中贡献相同，所以要除以4\n",[31,884,885,888,891,893,896,899,902,905,908,911,913,916,918,921,923,925,927,930,933,935,938,940],{"class":33,"line":501},[31,886,887],{"class":51},"    this",[31,889,890],{"class":673},"->vx ",[31,892,776],{"class":639},[31,894,895],{"class":673}," ( encoder_wheel_velocities_[",[31,897,898],{"class":51},"0",[31,900,901],{"class":673},"] ",[31,903,904],{"class":639},"+",[31,906,907],{"class":673}," encoder_wheel_velocities_[",[31,909,910],{"class":51},"1",[31,912,901],{"class":673},[31,914,915],{"class":639},"-",[31,917,907],{"class":673},[31,919,920],{"class":51},"2",[31,922,901],{"class":673},[31,924,915],{"class":639},[31,926,907],{"class":673},[31,928,929],{"class":51},"3",[31,931,932],{"class":673},"]) ",[31,934,859],{"class":639},[31,936,937],{"class":51}," 4.0",[31,939,843],{"class":639},[31,941,867],{"class":673},[31,943,944,946,949,951,953,955,957,959,961,963,965,967,969,971,973,975,977,979,981,983,985,987],{"class":33,"line":512},[31,945,887],{"class":51},[31,947,948],{"class":673},"->vy ",[31,950,776],{"class":639},[31,952,895],{"class":673},[31,954,898],{"class":51},[31,956,901],{"class":673},[31,958,915],{"class":639},[31,960,907],{"class":673},[31,962,910],{"class":51},[31,964,901],{"class":673},[31,966,915],{"class":639},[31,968,907],{"class":673},[31,970,920],{"class":51},[31,972,901],{"class":673},[31,974,904],{"class":639},[31,976,907],{"class":673},[31,978,929],{"class":51},[31,980,932],{"class":673},[31,982,859],{"class":639},[31,984,937],{"class":51},[31,986,843],{"class":639},[31,988,867],{"class":673},[31,990,991],{"class":33,"line":519},[31,992,668],{"emptyLinePlaceholder":667},[31,994,995],{"class":33,"line":526},[31,996,997],{"class":261},"    //线速度，轮距（wheel_spacing） 决定了左右轮对旋转的贡献程度，轴距（alex_spacing） 决定了前后轮对旋转的贡献程度，\n",[31,999,1000],{"class":33,"line":533},[31,1001,1002],{"class":261},"    //所以要除以底盘尺寸，alex_spacing + wheel_spacing 是底盘尺寸。\n",[31,1004,1006,1008,1011,1013,1016,1018,1021,1023,1025,1027,1029,1031,1033,1035,1037,1039,1041,1043,1045,1047,1049,1051,1053,1056,1058,1060,1063,1065],{"class":33,"line":1005},33,[31,1007,887],{"class":51},[31,1009,1010],{"class":673},"->vw ",[31,1012,776],{"class":639},[31,1014,1015],{"class":673}," (",[31,1017,915],{"class":639},[31,1019,1020],{"class":673},"encoder_wheel_velocities_[",[31,1022,898],{"class":51},[31,1024,901],{"class":673},[31,1026,915],{"class":639},[31,1028,907],{"class":673},[31,1030,910],{"class":51},[31,1032,901],{"class":673},[31,1034,915],{"class":639},[31,1036,907],{"class":673},[31,1038,920],{"class":51},[31,1040,901],{"class":673},[31,1042,915],{"class":639},[31,1044,907],{"class":673},[31,1046,929],{"class":51},[31,1048,932],{"class":673},[31,1050,859],{"class":639},[31,1052,1015],{"class":673},[31,1054,1055],{"class":51},"4.0",[31,1057,843],{"class":639},[31,1059,846],{"class":639},[31,1061,1062],{"class":673}," (Wheel_Spacing ",[31,1064,904],{"class":639},[31,1066,1067],{"class":673}," Alex_Spacing));\n",[31,1069,1071],{"class":33,"line":1070},34,[31,1072,668],{"emptyLinePlaceholder":667},[31,1074,1076],{"class":33,"line":1075},35,[31,1077,1078],{"class":261},"    // 更新机器人的位置（假设机器人沿着y轴移动）\n",[31,1080,1082],{"class":33,"line":1081},36,[31,1083,1084],{"class":261},"//     this->x_position += this->vx * std::__math::cos(this->yaw) * this->dt;  \n",[31,1086,1088],{"class":33,"line":1087},37,[31,1089,1090],{"class":261},"//     this->y_position += this->vy * std::__math::sin(this->yaw) * this->dt;\n",[31,1092,1094,1096,1099,1102,1105,1107,1109,1112,1114,1117,1120,1122,1124],{"class":33,"line":1093},38,[31,1095,887],{"class":51},[31,1097,1098],{"class":673},"->x_position ",[31,1100,1101],{"class":639},"+=",[31,1103,1104],{"class":51}," this",[31,1106,890],{"class":673},[31,1108,837],{"class":639},[31,1110,1111],{"class":37}," arm_cos_f32",[31,1113,750],{"class":673},[31,1115,1116],{"class":51},"this",[31,1118,1119],{"class":673},"->yaw) ",[31,1121,837],{"class":639},[31,1123,1104],{"class":51},[31,1125,1126],{"class":673},"->dt;  \n",[31,1128,1130,1132,1135,1137,1139,1141,1143,1146,1148,1150,1152,1154,1156],{"class":33,"line":1129},39,[31,1131,887],{"class":51},[31,1133,1134],{"class":673},"->y_position ",[31,1136,1101],{"class":639},[31,1138,1104],{"class":51},[31,1140,948],{"class":673},[31,1142,837],{"class":639},[31,1144,1145],{"class":37}," arm_sin_f32",[31,1147,750],{"class":673},[31,1149,1116],{"class":51},[31,1151,1119],{"class":673},[31,1153,837],{"class":639},[31,1155,1104],{"class":51},[31,1157,1158],{"class":673},"->dt;\n",[31,1160,1162,1164,1167,1169,1171,1173,1175,1177],{"class":33,"line":1161},40,[31,1163,887],{"class":51},[31,1165,1166],{"class":673},"->yaw ",[31,1168,1101],{"class":639},[31,1170,1104],{"class":51},[31,1172,1010],{"class":673},[31,1174,837],{"class":639},[31,1176,1104],{"class":51},[31,1178,1158],{"class":673},[31,1180,1182],{"class":33,"line":1181},41,[31,1183,668],{"emptyLinePlaceholder":667},[31,1185,1187],{"class":33,"line":1186},42,[31,1188,1189],{"class":261},"    // 保证 yaw 始终在 -PI 到 PI 之间\n",[31,1191,1193,1196,1198,1200,1202,1205,1207,1209],{"class":33,"line":1192},43,[31,1194,1195],{"class":639},"    if",[31,1197,750],{"class":673},[31,1199,1116],{"class":51},[31,1201,1166],{"class":673},[31,1203,1204],{"class":639},">",[31,1206,849],{"class":51},[31,1208,843],{"class":639},[31,1210,1211],{"class":673},") \n",[31,1213,1215],{"class":33,"line":1214},44,[31,1216,819],{"class":673},[31,1218,1220,1223,1225,1228,1230,1232,1234,1236],{"class":33,"line":1219},45,[31,1221,1222],{"class":51},"      this",[31,1224,1166],{"class":673},[31,1226,1227],{"class":639},"-=",[31,1229,840],{"class":51},[31,1231,846],{"class":639},[31,1233,849],{"class":51},[31,1235,843],{"class":639},[31,1237,867],{"class":673},[31,1239,1241],{"class":33,"line":1240},46,[31,1242,872],{"class":673},[31,1244,1246,1248,1250,1252,1254,1256,1259,1262,1264],{"class":33,"line":1245},47,[31,1247,1195],{"class":639},[31,1249,750],{"class":673},[31,1251,1116],{"class":51},[31,1253,1166],{"class":673},[31,1255,803],{"class":639},[31,1257,1258],{"class":639}," -",[31,1260,1261],{"class":51},"3.14159265358979",[31,1263,843],{"class":639},[31,1265,1211],{"class":673},[31,1267,1269],{"class":33,"line":1268},48,[31,1270,819],{"class":673},[31,1272,1274,1276,1278,1280,1282,1284,1286,1288],{"class":33,"line":1273},49,[31,1275,1222],{"class":51},[31,1277,1166],{"class":673},[31,1279,1101],{"class":639},[31,1281,840],{"class":51},[31,1283,846],{"class":639},[31,1285,849],{"class":51},[31,1287,843],{"class":639},[31,1289,867],{"class":673},[31,1291,1293],{"class":33,"line":1292},50,[31,1294,872],{"class":673},[31,1296,1298],{"class":33,"line":1297},51,[31,1299,668],{"emptyLinePlaceholder":667},[31,1301,1303],{"class":33,"line":1302},52,[31,1304,1305],{"class":261},"//    this->yaw_deg = this->yaw *  180.0f / 3.14159265358979f;\n",[31,1307,1309],{"class":33,"line":1308},53,[31,1310,668],{"emptyLinePlaceholder":667},[31,1312,1314],{"class":33,"line":1313},54,[31,1315,1316],{"class":673},"}\n",[14,1318,1319],{},"ROS2總代碼如下：",[21,1321,1323],{"className":630,"code":1322,"language":632,"meta":26,"style":26},"#include \"rclcpp/rclcpp.hpp\"\n#include \"serial_driver/serial_driver.hpp\"\n#include \u003Cchrono>\n#include \u003Cfunctional>\n#include \u003Crclcpp/logging.hpp>\n#include \u003Cstring>\n#include \"sensor04_odom_kc/serial_pack.h\"\n#include \"geometry_msgs/msg/twist.hpp\"\n#include \"nav_msgs/msg/odometry.hpp\"\n#include \u003Ctf2/LinearMath/Quaternion.h>\n#include \u003Ctf2_ros/transform_broadcaster.h>\n\nextern std::vector\u003Cuint8_t> tx_data_buffer;\n\nclass Odom_KC_Node : public rclcpp::Node\n{\npublic:\n  Odom_KC_Node() : Node(\"Odom_KC_Node\")\n  {\n    // 声明参数（带默认值）\n    // 串口设备默认名（根据实际设备调整）\n    this->declare_parameter(\"device_name\", \"/dev/ttyACM1\");\n    //串口默认波特率\n    this->declare_parameter(\"baud_rate\", 115200);\n\n    // 获取参数值\n    const std::string device_name = this->get_parameter(\"device_name\").as_string();\n    const uint32_t baud_rate = this->get_parameter(\"baud_rate\").as_int();\n\n    RCLCPP_INFO(this->get_logger(), \"Serial port Node Open!\");\n    // 创建串口配置对象\n    // 波特率默认115200；不开启流控制；无奇偶效验；停止位1。\n    drivers::serial_driver::SerialPortConfig config(\n        baud_rate,\n        drivers::serial_driver::FlowControl::NONE,\n        drivers::serial_driver::Parity::NONE,\n        drivers::serial_driver::StopBits::ONE);\n\n    // 初始化串口\n    try\n    {\n      io_context_ = std::make_shared\u003Cdrivers::common::IoContext>(1);\n      // 初始化 serial_driver_\n      serial_driver_ = std::make_shared\u003Cdrivers::serial_driver::SerialDriver>(*io_context_);\n      serial_driver_->init_port(device_name, config);\n      serial_driver_->port()->open();\n\n      RCLCPP_INFO(this->get_logger(), \"Serial port initialized successfully\");\n      RCLCPP_INFO(this->get_logger(), \"Using device: %s\", serial_driver_->port().get()->device_name().c_str());\n      RCLCPP_INFO(this->get_logger(), \"Baud_rate: %d\", config.get_baud_rate());\n    }\n    catch (const std::exception &ex)\n    {\n      RCLCPP_ERROR(this->get_logger(), \"Failed to initialize serial port: %s\", ex.what());\n      return;\n    }\n\n    //串口发布方\n    odom_pub_ = this->create_publisher\u003Cnav_msgs::msg::Odometry>(\"odom\",10);\n\n    //初始化tf广播器\n    tf_broadcaster_ = std::make_unique\u003Ctf2_ros::TransformBroadcaster>(*this);\n\n    //初始化cmd_vel消息订阅\n    cmd_vel_sub_ = this->create_subscription\u003Cgeometry_msgs::msg::Twist>(\"cmd_vel\",10,std::bind(&Odom_KC_Node::cmd_vel_sub_callback,this,std::placeholders::_1));\n\n    async_receive_message();   //进入异步接收\n  }\n\nprivate:\n  std::shared_ptr\u003Cdrivers::serial_driver::SerialDriver> serial_driver_;\n  std::shared_ptr\u003Cdrivers::common::IoContext> io_context_;\n\n  rclcpp::Publisher\u003Cnav_msgs::msg::Odometry>::SharedPtr odom_pub_;\n  std::unique_ptr\u003Ctf2_ros::TransformBroadcaster> tf_broadcaster_;\n\n  rclcpp::Subscription\u003Cgeometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_;\n\n  // // 四个轮子的速度(对应单片机的顺序)（单位：rpm）\n  // fp32 received_encoder_wheel_velocities_[4] = {0.0, 0.0, 0.0, 0.0};\n  // // 四个轮子的速度(对应单片机的顺序)（单位：m/s）\n  // fp32 encoder_wheel_velocities_[4] = {0.0, 0.0, 0.0, 0.0};  \n\n  // // 四个轮子的速度(对应单片机的顺序)（单位：2000pc）\n  // fp32 received_encoder_wheel_angle_[4] = {0.0, 0.0, 0.0, 0.0};\n\n  //麦克纳姆轮底盘参数\n  const fp32 wheel_spacing = 0.093; // 轮间距（单位：米）\n  const fp32 alex_spacing = 0.085; // 轮距（单位：米）\n  const fp32 wheel_radius_ = 0.0375; // 轮子半径（单位：米）\n\n  fp32 vy=0.0,vx=0.0,vw=0.0;\n  fp32 yaw_ = 0.0; // 机器人航向角（单位：弧度）\n  fp32 dt_;\n\n  fp32 x_position_ = 0.0; // x位置\n  fp32 y_position_ = 0.0; // y位置\n\n  void async_receive_message()  //创建一个函数更方便重新调用\n  {\n    auto port = serial_driver_->port();\n\n    // 设置接收回调函数\n    port->async_receive([this](const std::vector\u003Cuint8_t> &data,const size_t &size) \n    {\n      //创建odom消息类型\n      auto odom_msg = nav_msgs::msg::Odometry();\n\n        if (size > 0)\n        {\n          for(int16_t i = 0;i \u003C (int16_t)size;++i)\n          {\n            uint8_t data_buffer = data[i];\n            // 处理接收到的数据\n            serial_pack_.rx.Data_Analysis(\n              &data_buffer,\n              0x01,\n            0,\n            0,\n            0,\n            0,\n            8);\n          }\n          //由于在ROS2中，node是局部变量，所以发布方只能在node类里，故Data_Apply不写任何东西，直接在接收下面的回调函数里实现功能。\n          if(serial_pack_.rx.data.cmd == 0x01)\n          {\n            RCLCPP_DEBUG(this->get_logger(), \"\\n\");\n            RCLCPP_DEBUG(this->get_logger(), \"以下是电机编码器的odom数据：\");\n\n            // // 存储电机速度数据\n            // received_encoder_wheel_velocities_[0] = serial_pack_.rx.data.fp32_buffer[0];  // 电机 0 速度\n            // received_encoder_wheel_velocities_[1] = serial_pack_.rx.data.fp32_buffer[1];  // 电机 1 速度\n            // received_encoder_wheel_velocities_[2] = serial_pack_.rx.data.fp32_buffer[2];  // 电机 2 速度\n            // received_encoder_wheel_velocities_[3] = serial_pack_.rx.data.fp32_buffer[3];  // 电机 3 速度\n\n            // // 存储电机位置数据\n            // received_encoder_wheel_angle_[0] = serial_pack_.rx.data.fp32_buffer[4];  // 电机 0 位置\n            // received_encoder_wheel_angle_[1] = serial_pack_.rx.data.fp32_buffer[5];  // 电机 1 位置\n            // received_encoder_wheel_angle_[2] = serial_pack_.rx.data.fp32_buffer[6];  // 电机 2 位置\n            // received_encoder_wheel_angle_[3] = serial_pack_.rx.data.fp32_buffer[7];  // 电机 3 位置\n\n            // vx = serial_pack_.rx.data.fp32_buffer[8];\n            // vy = serial_pack_.rx.data.fp32_buffer[9];\n            // vw = serial_pack_.rx.data.fp32_buffer[10];\n            // yaw_ = serial_pack_.rx.data.fp32_buffer[11];\n            // dt_ = serial_pack_.rx.data.fp32_buffer[12];\n            // x_position_ = serial_pack_.rx.data.fp32_buffer[13];\n            // y_position_ = serial_pack_.rx.data.fp32_buffer[14];\n\n            vx = serial_pack_.rx.data.fp32_buffer[0];\n            vy = serial_pack_.rx.data.fp32_buffer[1];\n            vw = serial_pack_.rx.data.fp32_buffer[2];\n            yaw_ = serial_pack_.rx.data.fp32_buffer[3];\n            dt_ = serial_pack_.rx.data.fp32_buffer[4];\n            x_position_ = serial_pack_.rx.data.fp32_buffer[5];\n            y_position_ = serial_pack_.rx.data.fp32_buffer[6];\n\n            // 打印电机速度和位置（角度）\n            for (int i = 0; i \u003C 4; ++i) \n            {\n                // RCLCPP_DEBUG(this->get_logger(), \"%d号电机的速度: %.6f RPM, 位置: %.6f (2000pc)\",\n                //             i, received_encoder_wheel_velocities_[i], received_encoder_wheel_angle_[i]);\n\n                RCLCPP_DEBUG(this->get_logger(),\"线速度:x:%.6f,y:%.6f,z:%.6f\",vx,vy,0.0f);\n                RCLCPP_DEBUG(this->get_logger(),\"角速度:x:%.6f,y:%.6f,z:%.6f\",0.0f,0.0f,vw);\n                RCLCPP_DEBUG(this->get_logger(),\"欧拉角(逆正顺负):r:%.6f,p:%.6f,y:%.6f\",0.0f,0.0f,yaw_);\n                RCLCPP_DEBUG(this->get_logger(),\"积分间隔:%.6f\",dt_);\n                RCLCPP_DEBUG(this->get_logger(),\"右手坐标系X坐标(前正后负):%.6f\",x_position_);\n                RCLCPP_DEBUG(this->get_logger(),\"右手坐标系Y坐标(左正右负):%.6f\",y_position_);\n            }\n\n            //时间戳\n            odom_msg.header.stamp = this->get_clock()->now();\n\n            //位姿信息所参考的坐标系\n            odom_msg.header.frame_id = \"odom\";\n\n            // 设置child_frame_id（底盘坐标系）\n            odom_msg.child_frame_id = \"base_link\";  // 设置子坐标系为机器人底盘坐标系\n\n            //DOF平动位置\n            odom_msg.pose.pose.position.x = x_position_;\n            odom_msg.pose.pose.position.y = y_position_;\n            odom_msg.pose.pose.position.z = 0.0;\n\n            //从欧拉角转换为四元数\n            tf2::Quaternion q;\n            q.setRPY(0,0,yaw_);\n            //DOF转动（四元数）\n            odom_msg.pose.pose.orientation.x = q.x();\n            odom_msg.pose.pose.orientation.y = q.y();\n            odom_msg.pose.pose.orientation.z = q.z();\n            odom_msg.pose.pose.orientation.w = q.w();\n\n            //线速度\n            odom_msg.twist.twist.linear.x = vx;\n            odom_msg.twist.twist.linear.y = vy;\n            odom_msg.twist.twist.linear.z = 0.0;\n\n            //角速度\n            odom_msg.twist.twist.angular.x = 0.0;\n            odom_msg.twist.twist.angular.y = 0.0;\n            odom_msg.twist.twist.angular.z = vw;\n\n            // 发布消息\n            odom_pub_->publish(odom_msg);\n\n            // 打印位置（XYZ）\n            RCLCPP_DEBUG(\n              this->get_logger(),\n              \"位置Position(XYZ): %.6f, %.6f, %.6f\",\n              odom_msg.pose.pose.position.x,\n              odom_msg.pose.pose.position.y,\n              odom_msg.pose.pose.position.z\n            );\n\n            // 打印姿态（四元数WXYZ）\n            RCLCPP_DEBUG(\n              this->get_logger(),\n              \"姿态Orientation(WXYZ): %.6f, %.6f, %.6f, %.6f\",\n              odom_msg.pose.pose.orientation.w,  // 注意顺序：WXYZ\n              odom_msg.pose.pose.orientation.x,\n              odom_msg.pose.pose.orientation.y,\n              odom_msg.pose.pose.orientation.z\n            );\n\n            // 打印姿态（欧拉角RPY）\n            RCLCPP_DEBUG(\n              this->get_logger(),\n              \"欧拉角Euler(RPY): %.6f, %.6f, %.6f\",\n              0.0,\n              0.0,\n              yaw_\n            );\n\n            // 打印线速度（XYZ）\n            RCLCPP_DEBUG(\n              this->get_logger(),\n              \"线速度LinearVel(XYZ): %.6f, %.6f, %.6f\",\n              odom_msg.twist.twist.linear.x,\n              odom_msg.twist.twist.linear.y,\n              odom_msg.twist.twist.linear.z\n            );\n\n            // 打印角速度（XYZ）\n            RCLCPP_DEBUG(\n              this->get_logger(),\n              \"角速度AngularVel(XYZ): %.6f, %.6f, %.6f\",\n              odom_msg.twist.twist.angular.x,\n              odom_msg.twist.twist.angular.y,\n              odom_msg.twist.twist.angular.z\n            );\n\n            /* 接下来发布tf */\n            auto transform = geometry_msgs::msg::TransformStamped();\n            transform.header.stamp = odom_msg.header.stamp; // 时间戳与odom同步\n            transform.header.frame_id = \"odom\";\n            transform.child_frame_id = \"base_link\";\n            transform.transform.translation.x = x_position_;\n            transform.transform.translation.y = y_position_;\n            transform.transform.translation.z = 0.0;\n            transform.transform.rotation = odom_msg.pose.pose.orientation; // 复用四元数\n            tf_broadcaster_->sendTransform(transform);\n          }\n\n        }\n        // 继续监听新的数据\n        async_receive_message();\n    }\n    );\n  }\n\n  void cmd_vel_sub_callback(const geometry_msgs::msg::Twist &cmd_msg)\n  {\n    // bool bool_buffer[] = {1, 0, 1, 0};\n    // int8_t int8_buffer[] = {0x11,0x22};\n    // int16_t int16_buffer[] = {2000,6666};\n    // int32_t int32_buffer[] = {305419896};\n    fp32 fp32_buffer[] = {(fp32)cmd_msg.linear.x,(fp32)cmd_msg.linear.y,(fp32)cmd_msg.linear.z,\n                          (fp32)cmd_msg.angular.x,(fp32)cmd_msg.angular.y,(fp32)cmd_msg.angular.z};\n\n    //由于ROS2中node为局部变量，所以只能在node中调用send函数，所以Serial_Transmit只负责处理data_buffer。\n    serial_pack_.tx.Data_Pack(0x01, \n                                 nullptr, 0,\n                                 nullptr, 0,\n                                 nullptr, 0,\n                                 nullptr, 0,\n                                 fp32_buffer, sizeof(fp32_buffer) / sizeof(fp32));\n\n    auto port = serial_driver_->port();\n\n    try\n    {\n      size_t bytes_size = port->send(tx_data_buffer);\n\n      RCLCPP_DEBUG(this->get_logger(), \"平动XYZ：%.6f,%.6f,%.6f\", fp32_buffer[0],fp32_buffer[1],fp32_buffer[2]);\n      RCLCPP_DEBUG(this->get_logger(), \"转动XYZ：%.6f,%.6f,%.6f\", fp32_buffer[3],fp32_buffer[4],fp32_buffer[5]);\n      RCLCPP_DEBUG(this->get_logger(), \"(%ld bytes)\", bytes_size);\n    }\n    catch(const std::exception &ex)\n    {\n      RCLCPP_ERROR(this->get_logger(), \"Error Transmiting from serial port:%s\",ex.what());\n    }\n  }\n};\n\nint main(int argc, char **argv)\n{\n  rclcpp::init(argc, argv);\n\n  auto node = std::make_shared\u003COdom_KC_Node>();\n\n  rclcpp::spin(node);\n\n  rclcpp::shutdown();\n  return 0;\n}\n",[28,1324,1325,1332,1339,1346,1353,1360,1367,1374,1381,1388,1395,1402,1406,1422,1426,1447,1451,1456,1474,1479,1484,1489,1513,1518,1538,1542,1547,1579,1608,1612,1634,1639,1644,1663,1668,1685,1700,1716,1720,1725,1730,1734,1770,1775,1808,1819,1834,1838,1858,1905,1935,1939,1960,1964,1994,2002,2007,2012,2018,2059,2064,2070,2103,2108,2114,2184,2189,2201,2207,2212,2218,2243,2266,2271,2298,2318,2323,2349,2354,2363,2369,2377,2383,2388,2396,2402,2407,2413,2433,2451,2469,2474,2501,2517,2523,2528,2543,2558,2563,2578,2583,2601,2606,2612,2666,2671,2677,2700,2705,2720,2726,2758,2764,2778,2784,2795,2804,2816,2824,2831,2838,2845,2853,2859,2865,2884,2889,2914,2934,2939,2948,2957,2966,2975,2984,2989,2997,3006,3015,3024,3033,3038,3044,3050,3056,3062,3068,3074,3080,3085,3101,3115,3129,3143,3158,3173,3188,3193,3199,3231,3237,3243,3249,3254,3298,3343,3389,3414,3439,3464,3470,3475,3481,3503,3508,3514,3527,3532,3538,3554,3559,3565,3576,3587,3599,3604,3610,3619,3638,3644,3660,3675,3690,3705,3710,3716,3727,3738,3750,3755,3761,3773,3785,3796,3801,3807,3819,3824,3830,3837,3850,3870,3876,3882,3888,3894,3899,3905,3912,3923,3947,3956,3962,3968,3974,3979,3984,3990,3997,4008,4028,4036,4043,4049,4054,4059,4065,4072,4083,4103,4109,4115,4121,4126,4131,4137,4144,4155,4175,4181,4187,4193,4198,4203,4209,4233,4247,4259,4271,4281,4291,4303,4317,4329,4334,4339,4345,4351,4359,4364,4370,4375,4380,4409,4414,4420,4426,4432,4438,4449,4455,4460,4466,4485,4497,4508,4519,4530,4550,4555,4570,4575,4580,4585,4605,4610,4658,4702,4729,4734,4751,4756,4785,4790,4795,4801,4806,4834,4839,4852,4857,4881,4886,4899,4904,4916,4926],{"__ignoreMap":26},[31,1326,1327,1329],{"class":33,"line":34},[31,1328,640],{"class":639},[31,1330,1331],{"class":41}," \"rclcpp/rclcpp.hpp\"\n",[31,1333,1334,1336],{"class":33,"line":265},[31,1335,640],{"class":639},[31,1337,1338],{"class":41}," \"serial_driver/serial_driver.hpp\"\n",[31,1340,1341,1343],{"class":33,"line":277},[31,1342,640],{"class":639},[31,1344,1345],{"class":41}," \u003Cchrono>\n",[31,1347,1348,1350],{"class":33,"line":286},[31,1349,640],{"class":639},[31,1351,1352],{"class":41}," \u003Cfunctional>\n",[31,1354,1355,1357],{"class":33,"line":295},[31,1356,640],{"class":639},[31,1358,1359],{"class":41}," \u003Crclcpp/logging.hpp>\n",[31,1361,1362,1364],{"class":33,"line":307},[31,1363,640],{"class":639},[31,1365,1366],{"class":41}," \u003Cstring>\n",[31,1368,1369,1371],{"class":33,"line":313},[31,1370,640],{"class":639},[31,1372,1373],{"class":41}," \"sensor04_odom_kc/serial_pack.h\"\n",[31,1375,1376,1378],{"class":33,"line":322},[31,1377,640],{"class":639},[31,1379,1380],{"class":41}," \"geometry_msgs/msg/twist.hpp\"\n",[31,1382,1383,1385],{"class":33,"line":328},[31,1384,640],{"class":639},[31,1386,1387],{"class":41}," \"nav_msgs/msg/odometry.hpp\"\n",[31,1389,1390,1392],{"class":33,"line":337},[31,1391,640],{"class":639},[31,1393,1394],{"class":41}," \u003Ctf2/LinearMath/Quaternion.h>\n",[31,1396,1397,1399],{"class":33,"line":345},[31,1398,640],{"class":639},[31,1400,1401],{"class":41}," \u003Ctf2_ros/transform_broadcaster.h>\n",[31,1403,1404],{"class":33,"line":357},[31,1405,668],{"emptyLinePlaceholder":667},[31,1407,1408,1410,1413,1416,1419],{"class":33,"line":366},[31,1409,702],{"class":639},[31,1411,1412],{"class":37}," std",[31,1414,1415],{"class":673},"::vector",[31,1417,1418],{"class":639},"\u003Cuint8_t>",[31,1420,1421],{"class":673}," tx_data_buffer;\n",[31,1423,1424],{"class":33,"line":374},[31,1425,668],{"emptyLinePlaceholder":667},[31,1427,1428,1431,1434,1437,1440,1442,1444],{"class":33,"line":382},[31,1429,1430],{"class":639},"class",[31,1432,1433],{"class":37}," Odom_KC_Node",[31,1435,1436],{"class":673}," : ",[31,1438,1439],{"class":639},"public",[31,1441,61],{"class":37},[31,1443,744],{"class":673},[31,1445,1446],{"class":37},"Node\n",[31,1448,1449],{"class":33,"line":394},[31,1450,765],{"class":673},[31,1452,1453],{"class":33,"line":405},[31,1454,1455],{"class":639},"public:\n",[31,1457,1458,1461,1464,1467,1469,1472],{"class":33,"line":415},[31,1459,1460],{"class":37},"  Odom_KC_Node",[31,1462,1463],{"class":673},"() : ",[31,1465,1466],{"class":37},"Node",[31,1468,750],{"class":673},[31,1470,1471],{"class":41},"\"Odom_KC_Node\"",[31,1473,760],{"class":673},[31,1475,1476],{"class":33,"line":425},[31,1477,1478],{"class":673},"  {\n",[31,1480,1481],{"class":33,"line":436},[31,1482,1483],{"class":261},"    // 声明参数（带默认值）\n",[31,1485,1486],{"class":33,"line":445},[31,1487,1488],{"class":261},"    // 串口设备默认名（根据实际设备调整）\n",[31,1490,1491,1493,1496,1499,1501,1504,1507,1510],{"class":33,"line":451},[31,1492,887],{"class":51},[31,1494,1495],{"class":673},"->",[31,1497,1498],{"class":37},"declare_parameter",[31,1500,750],{"class":673},[31,1502,1503],{"class":41},"\"device_name\"",[31,1505,1506],{"class":673},", ",[31,1508,1509],{"class":41},"\"/dev/ttyACM1\"",[31,1511,1512],{"class":673},");\n",[31,1514,1515],{"class":33,"line":460},[31,1516,1517],{"class":261},"    //串口默认波特率\n",[31,1519,1520,1522,1524,1526,1528,1531,1533,1536],{"class":33,"line":468},[31,1521,887],{"class":51},[31,1523,1495],{"class":673},[31,1525,1498],{"class":37},[31,1527,750],{"class":673},[31,1529,1530],{"class":41},"\"baud_rate\"",[31,1532,1506],{"class":673},[31,1534,1535],{"class":51},"115200",[31,1537,1512],{"class":673},[31,1539,1540],{"class":33,"line":480},[31,1541,668],{"emptyLinePlaceholder":667},[31,1543,1544],{"class":33,"line":487},[31,1545,1546],{"class":261},"    // 获取参数值\n",[31,1548,1549,1552,1554,1557,1559,1561,1563,1566,1568,1570,1573,1576],{"class":33,"line":494},[31,1550,1551],{"class":639},"    const",[31,1553,1412],{"class":37},[31,1555,1556],{"class":673},"::string device_name ",[31,1558,776],{"class":639},[31,1560,1104],{"class":51},[31,1562,1495],{"class":673},[31,1564,1565],{"class":37},"get_parameter",[31,1567,750],{"class":673},[31,1569,1503],{"class":41},[31,1571,1572],{"class":673},").",[31,1574,1575],{"class":37},"as_string",[31,1577,1578],{"class":673},"();\n",[31,1580,1581,1583,1586,1589,1591,1593,1595,1597,1599,1601,1603,1606],{"class":33,"line":501},[31,1582,1551],{"class":639},[31,1584,1585],{"class":639}," uint32_t",[31,1587,1588],{"class":673}," baud_rate ",[31,1590,776],{"class":639},[31,1592,1104],{"class":51},[31,1594,1495],{"class":673},[31,1596,1565],{"class":37},[31,1598,750],{"class":673},[31,1600,1530],{"class":41},[31,1602,1572],{"class":673},[31,1604,1605],{"class":37},"as_int",[31,1607,1578],{"class":673},[31,1609,1610],{"class":33,"line":512},[31,1611,668],{"emptyLinePlaceholder":667},[31,1613,1614,1617,1619,1621,1623,1626,1629,1632],{"class":33,"line":519},[31,1615,1616],{"class":37},"    RCLCPP_INFO",[31,1618,750],{"class":673},[31,1620,1116],{"class":51},[31,1622,1495],{"class":673},[31,1624,1625],{"class":37},"get_logger",[31,1627,1628],{"class":673},"(), ",[31,1630,1631],{"class":41},"\"Serial port Node Open!\"",[31,1633,1512],{"class":673},[31,1635,1636],{"class":33,"line":526},[31,1637,1638],{"class":261},"    // 创建串口配置对象\n",[31,1640,1641],{"class":33,"line":533},[31,1642,1643],{"class":261},"    // 波特率默认115200；不开启流控制；无奇偶效验；停止位1。\n",[31,1645,1646,1649,1651,1654,1657,1660],{"class":33,"line":1005},[31,1647,1648],{"class":37},"    drivers",[31,1650,744],{"class":673},[31,1652,1653],{"class":37},"serial_driver",[31,1655,1656],{"class":673},"::SerialPortConfig ",[31,1658,1659],{"class":37},"config",[31,1661,1662],{"class":673},"(\n",[31,1664,1665],{"class":33,"line":1070},[31,1666,1667],{"class":673},"        baud_rate,\n",[31,1669,1670,1673,1675,1677,1679,1682],{"class":33,"line":1075},[31,1671,1672],{"class":37},"        drivers",[31,1674,744],{"class":673},[31,1676,1653],{"class":37},[31,1678,744],{"class":673},[31,1680,1681],{"class":37},"FlowControl",[31,1683,1684],{"class":673},"::NONE,\n",[31,1686,1687,1689,1691,1693,1695,1698],{"class":33,"line":1081},[31,1688,1672],{"class":37},[31,1690,744],{"class":673},[31,1692,1653],{"class":37},[31,1694,744],{"class":673},[31,1696,1697],{"class":37},"Parity",[31,1699,1684],{"class":673},[31,1701,1702,1704,1706,1708,1710,1713],{"class":33,"line":1087},[31,1703,1672],{"class":37},[31,1705,744],{"class":673},[31,1707,1653],{"class":37},[31,1709,744],{"class":673},[31,1711,1712],{"class":37},"StopBits",[31,1714,1715],{"class":673},"::ONE);\n",[31,1717,1718],{"class":33,"line":1093},[31,1719,668],{"emptyLinePlaceholder":667},[31,1721,1722],{"class":33,"line":1129},[31,1723,1724],{"class":261},"    // 初始化串口\n",[31,1726,1727],{"class":33,"line":1161},[31,1728,1729],{"class":639},"    try\n",[31,1731,1732],{"class":33,"line":1181},[31,1733,819],{"class":673},[31,1735,1736,1739,1741,1743,1745,1748,1750,1753,1755,1758,1760,1763,1766,1768],{"class":33,"line":1186},[31,1737,1738],{"class":673},"      io_context_ ",[31,1740,776],{"class":639},[31,1742,1412],{"class":37},[31,1744,744],{"class":673},[31,1746,1747],{"class":37},"make_shared",[31,1749,803],{"class":673},[31,1751,1752],{"class":37},"drivers",[31,1754,744],{"class":673},[31,1756,1757],{"class":37},"common",[31,1759,744],{"class":673},[31,1761,1762],{"class":37},"IoContext",[31,1764,1765],{"class":673},">(",[31,1767,910],{"class":51},[31,1769,1512],{"class":673},[31,1771,1772],{"class":33,"line":1192},[31,1773,1774],{"class":261},"      // 初始化 serial_driver_\n",[31,1776,1777,1780,1782,1784,1786,1788,1790,1792,1794,1796,1798,1801,1803,1805],{"class":33,"line":1214},[31,1778,1779],{"class":673},"      serial_driver_ ",[31,1781,776],{"class":639},[31,1783,1412],{"class":37},[31,1785,744],{"class":673},[31,1787,1747],{"class":37},[31,1789,803],{"class":673},[31,1791,1752],{"class":37},[31,1793,744],{"class":673},[31,1795,1653],{"class":37},[31,1797,744],{"class":673},[31,1799,1800],{"class":37},"SerialDriver",[31,1802,1765],{"class":673},[31,1804,837],{"class":639},[31,1806,1807],{"class":673},"io_context_);\n",[31,1809,1810,1813,1816],{"class":33,"line":1219},[31,1811,1812],{"class":673},"      serial_driver_->",[31,1814,1815],{"class":37},"init_port",[31,1817,1818],{"class":673},"(device_name, config);\n",[31,1820,1821,1823,1826,1829,1832],{"class":33,"line":1240},[31,1822,1812],{"class":673},[31,1824,1825],{"class":37},"port",[31,1827,1828],{"class":673},"()->",[31,1830,1831],{"class":37},"open",[31,1833,1578],{"class":673},[31,1835,1836],{"class":33,"line":1245},[31,1837,668],{"emptyLinePlaceholder":667},[31,1839,1840,1843,1845,1847,1849,1851,1853,1856],{"class":33,"line":1268},[31,1841,1842],{"class":37},"      RCLCPP_INFO",[31,1844,750],{"class":673},[31,1846,1116],{"class":51},[31,1848,1495],{"class":673},[31,1850,1625],{"class":37},[31,1852,1628],{"class":673},[31,1854,1855],{"class":41},"\"Serial port initialized successfully\"",[31,1857,1512],{"class":673},[31,1859,1860,1862,1864,1866,1868,1870,1872,1875,1878,1881,1884,1886,1889,1892,1894,1897,1899,1902],{"class":33,"line":1273},[31,1861,1842],{"class":37},[31,1863,750],{"class":673},[31,1865,1116],{"class":51},[31,1867,1495],{"class":673},[31,1869,1625],{"class":37},[31,1871,1628],{"class":673},[31,1873,1874],{"class":41},"\"Using device: ",[31,1876,1877],{"class":51},"%s",[31,1879,1880],{"class":41},"\"",[31,1882,1883],{"class":673},", serial_driver_->",[31,1885,1825],{"class":37},[31,1887,1888],{"class":673},"().",[31,1890,1891],{"class":37},"get",[31,1893,1828],{"class":673},[31,1895,1896],{"class":37},"device_name",[31,1898,1888],{"class":673},[31,1900,1901],{"class":37},"c_str",[31,1903,1904],{"class":673},"());\n",[31,1906,1907,1909,1911,1913,1915,1917,1919,1922,1925,1927,1930,1933],{"class":33,"line":1292},[31,1908,1842],{"class":37},[31,1910,750],{"class":673},[31,1912,1116],{"class":51},[31,1914,1495],{"class":673},[31,1916,1625],{"class":37},[31,1918,1628],{"class":673},[31,1920,1921],{"class":41},"\"Baud_rate: ",[31,1923,1924],{"class":51},"%d",[31,1926,1880],{"class":41},[31,1928,1929],{"class":673},", config.",[31,1931,1932],{"class":37},"get_baud_rate",[31,1934,1904],{"class":673},[31,1936,1937],{"class":33,"line":1297},[31,1938,872],{"class":673},[31,1940,1941,1944,1946,1949,1951,1954,1957],{"class":33,"line":1302},[31,1942,1943],{"class":639},"    catch",[31,1945,1015],{"class":673},[31,1947,1948],{"class":639},"const",[31,1950,1412],{"class":37},[31,1952,1953],{"class":673},"::exception ",[31,1955,1956],{"class":639},"&",[31,1958,1959],{"class":673},"ex)\n",[31,1961,1962],{"class":33,"line":1308},[31,1963,819],{"class":673},[31,1965,1966,1969,1971,1973,1975,1977,1979,1982,1984,1986,1989,1992],{"class":33,"line":1313},[31,1967,1968],{"class":37},"      RCLCPP_ERROR",[31,1970,750],{"class":673},[31,1972,1116],{"class":51},[31,1974,1495],{"class":673},[31,1976,1625],{"class":37},[31,1978,1628],{"class":673},[31,1980,1981],{"class":41},"\"Failed to initialize serial port: ",[31,1983,1877],{"class":51},[31,1985,1880],{"class":41},[31,1987,1988],{"class":673},", ex.",[31,1990,1991],{"class":37},"what",[31,1993,1904],{"class":673},[31,1995,1997,2000],{"class":33,"line":1996},55,[31,1998,1999],{"class":639},"      return",[31,2001,867],{"class":673},[31,2003,2005],{"class":33,"line":2004},56,[31,2006,872],{"class":673},[31,2008,2010],{"class":33,"line":2009},57,[31,2011,668],{"emptyLinePlaceholder":667},[31,2013,2015],{"class":33,"line":2014},58,[31,2016,2017],{"class":261},"    //串口发布方\n",[31,2019,2021,2024,2026,2028,2031,2033,2036,2038,2041,2044,2046,2048,2051,2054,2057],{"class":33,"line":2020},59,[31,2022,2023],{"class":673},"    odom_pub_ ",[31,2025,776],{"class":639},[31,2027,1104],{"class":51},[31,2029,2030],{"class":673},"->create_publisher",[31,2032,803],{"class":639},[31,2034,2035],{"class":37},"nav_msgs",[31,2037,744],{"class":673},[31,2039,2040],{"class":37},"msg",[31,2042,2043],{"class":673},"::Odometry",[31,2045,1204],{"class":639},[31,2047,750],{"class":673},[31,2049,2050],{"class":41},"\"odom\"",[31,2052,2053],{"class":673},",",[31,2055,2056],{"class":51},"10",[31,2058,1512],{"class":673},[31,2060,2062],{"class":33,"line":2061},60,[31,2063,668],{"emptyLinePlaceholder":667},[31,2065,2067],{"class":33,"line":2066},61,[31,2068,2069],{"class":261},"    //初始化tf广播器\n",[31,2071,2073,2076,2078,2080,2082,2085,2087,2090,2092,2095,2097,2099,2101],{"class":33,"line":2072},62,[31,2074,2075],{"class":673},"    tf_broadcaster_ ",[31,2077,776],{"class":639},[31,2079,1412],{"class":37},[31,2081,744],{"class":673},[31,2083,2084],{"class":37},"make_unique",[31,2086,803],{"class":673},[31,2088,2089],{"class":37},"tf2_ros",[31,2091,744],{"class":673},[31,2093,2094],{"class":37},"TransformBroadcaster",[31,2096,1765],{"class":673},[31,2098,837],{"class":639},[31,2100,1116],{"class":51},[31,2102,1512],{"class":673},[31,2104,2106],{"class":33,"line":2105},63,[31,2107,668],{"emptyLinePlaceholder":667},[31,2109,2111],{"class":33,"line":2110},64,[31,2112,2113],{"class":261},"    //初始化cmd_vel消息订阅\n",[31,2115,2117,2120,2122,2124,2127,2129,2132,2134,2136,2139,2141,2143,2146,2148,2150,2152,2155,2157,2160,2162,2164,2167,2170,2172,2174,2176,2178,2181],{"class":33,"line":2116},65,[31,2118,2119],{"class":673},"    cmd_vel_sub_ ",[31,2121,776],{"class":639},[31,2123,1104],{"class":51},[31,2125,2126],{"class":673},"->create_subscription",[31,2128,803],{"class":639},[31,2130,2131],{"class":37},"geometry_msgs",[31,2133,744],{"class":673},[31,2135,2040],{"class":37},[31,2137,2138],{"class":673},"::Twist",[31,2140,1204],{"class":639},[31,2142,750],{"class":673},[31,2144,2145],{"class":41},"\"cmd_vel\"",[31,2147,2053],{"class":673},[31,2149,2056],{"class":51},[31,2151,2053],{"class":673},[31,2153,2154],{"class":37},"std",[31,2156,744],{"class":673},[31,2158,2159],{"class":37},"bind",[31,2161,750],{"class":673},[31,2163,1956],{"class":639},[31,2165,2166],{"class":37},"Odom_KC_Node",[31,2168,2169],{"class":673},"::cmd_vel_sub_callback,",[31,2171,1116],{"class":51},[31,2173,2053],{"class":673},[31,2175,2154],{"class":37},[31,2177,744],{"class":673},[31,2179,2180],{"class":37},"placeholders",[31,2182,2183],{"class":673},"::_1));\n",[31,2185,2187],{"class":33,"line":2186},66,[31,2188,668],{"emptyLinePlaceholder":667},[31,2190,2192,2195,2198],{"class":33,"line":2191},67,[31,2193,2194],{"class":37},"    async_receive_message",[31,2196,2197],{"class":673},"();",[31,2199,2200],{"class":261},"   //进入异步接收\n",[31,2202,2204],{"class":33,"line":2203},68,[31,2205,2206],{"class":673},"  }\n",[31,2208,2210],{"class":33,"line":2209},69,[31,2211,668],{"emptyLinePlaceholder":667},[31,2213,2215],{"class":33,"line":2214},70,[31,2216,2217],{"class":639},"private:\n",[31,2219,2221,2224,2227,2229,2231,2233,2235,2238,2240],{"class":33,"line":2220},71,[31,2222,2223],{"class":37},"  std",[31,2225,2226],{"class":673},"::shared_ptr",[31,2228,803],{"class":639},[31,2230,1752],{"class":37},[31,2232,744],{"class":673},[31,2234,1653],{"class":37},[31,2236,2237],{"class":673},"::SerialDriver",[31,2239,1204],{"class":639},[31,2241,2242],{"class":673}," serial_driver_;\n",[31,2244,2246,2248,2250,2252,2254,2256,2258,2261,2263],{"class":33,"line":2245},72,[31,2247,2223],{"class":37},[31,2249,2226],{"class":673},[31,2251,803],{"class":639},[31,2253,1752],{"class":37},[31,2255,744],{"class":673},[31,2257,1757],{"class":37},[31,2259,2260],{"class":673},"::IoContext",[31,2262,1204],{"class":639},[31,2264,2265],{"class":673}," io_context_;\n",[31,2267,2269],{"class":33,"line":2268},73,[31,2270,668],{"emptyLinePlaceholder":667},[31,2272,2274,2277,2279,2282,2284,2286,2288,2290,2292,2295],{"class":33,"line":2273},74,[31,2275,2276],{"class":37},"  rclcpp",[31,2278,744],{"class":673},[31,2280,2281],{"class":37},"Publisher",[31,2283,803],{"class":673},[31,2285,2035],{"class":37},[31,2287,744],{"class":673},[31,2289,2040],{"class":37},[31,2291,744],{"class":673},[31,2293,2294],{"class":37},"Odometry",[31,2296,2297],{"class":673},">::SharedPtr odom_pub_;\n",[31,2299,2301,2303,2306,2308,2310,2313,2315],{"class":33,"line":2300},75,[31,2302,2223],{"class":37},[31,2304,2305],{"class":673},"::unique_ptr",[31,2307,803],{"class":639},[31,2309,2089],{"class":37},[31,2311,2312],{"class":673},"::TransformBroadcaster",[31,2314,1204],{"class":639},[31,2316,2317],{"class":673}," tf_broadcaster_;\n",[31,2319,2321],{"class":33,"line":2320},76,[31,2322,668],{"emptyLinePlaceholder":667},[31,2324,2326,2328,2330,2333,2335,2337,2339,2341,2343,2346],{"class":33,"line":2325},77,[31,2327,2276],{"class":37},[31,2329,744],{"class":673},[31,2331,2332],{"class":37},"Subscription",[31,2334,803],{"class":673},[31,2336,2131],{"class":37},[31,2338,744],{"class":673},[31,2340,2040],{"class":37},[31,2342,744],{"class":673},[31,2344,2345],{"class":37},"Twist",[31,2347,2348],{"class":673},">::SharedPtr cmd_vel_sub_;\n",[31,2350,2352],{"class":33,"line":2351},78,[31,2353,668],{"emptyLinePlaceholder":667},[31,2355,2357,2360],{"class":33,"line":2356},79,[31,2358,2359],{"class":261},"  //",[31,2361,2362],{"class":261}," // 四个轮子的速度(对应单片机的顺序)（单位：rpm）\n",[31,2364,2366],{"class":33,"line":2365},80,[31,2367,2368],{"class":261},"  // fp32 received_encoder_wheel_velocities_[4] = {0.0, 0.0, 0.0, 0.0};\n",[31,2370,2372,2374],{"class":33,"line":2371},81,[31,2373,2359],{"class":261},[31,2375,2376],{"class":261}," // 四个轮子的速度(对应单片机的顺序)（单位：m/s）\n",[31,2378,2380],{"class":33,"line":2379},82,[31,2381,2382],{"class":261},"  // fp32 encoder_wheel_velocities_[4] = {0.0, 0.0, 0.0, 0.0};  \n",[31,2384,2386],{"class":33,"line":2385},83,[31,2387,668],{"emptyLinePlaceholder":667},[31,2389,2391,2393],{"class":33,"line":2390},84,[31,2392,2359],{"class":261},[31,2394,2395],{"class":261}," // 四个轮子的速度(对应单片机的顺序)（单位：2000pc）\n",[31,2397,2399],{"class":33,"line":2398},85,[31,2400,2401],{"class":261},"  // fp32 received_encoder_wheel_angle_[4] = {0.0, 0.0, 0.0, 0.0};\n",[31,2403,2405],{"class":33,"line":2404},86,[31,2406,668],{"emptyLinePlaceholder":667},[31,2408,2410],{"class":33,"line":2409},87,[31,2411,2412],{"class":261},"  //麦克纳姆轮底盘参数\n",[31,2414,2416,2419,2422,2424,2427,2430],{"class":33,"line":2415},88,[31,2417,2418],{"class":639},"  const",[31,2420,2421],{"class":673}," fp32 wheel_spacing ",[31,2423,776],{"class":639},[31,2425,2426],{"class":51}," 0.093",[31,2428,2429],{"class":673},";",[31,2431,2432],{"class":261}," // 轮间距（单位：米）\n",[31,2434,2436,2438,2441,2443,2446,2448],{"class":33,"line":2435},89,[31,2437,2418],{"class":639},[31,2439,2440],{"class":673}," fp32 alex_spacing ",[31,2442,776],{"class":639},[31,2444,2445],{"class":51}," 0.085",[31,2447,2429],{"class":673},[31,2449,2450],{"class":261}," // 轮距（单位：米）\n",[31,2452,2454,2456,2459,2461,2464,2466],{"class":33,"line":2453},90,[31,2455,2418],{"class":639},[31,2457,2458],{"class":673}," fp32 wheel_radius_ ",[31,2460,776],{"class":639},[31,2462,2463],{"class":51}," 0.0375",[31,2465,2429],{"class":673},[31,2467,2468],{"class":261}," // 轮子半径（单位：米）\n",[31,2470,2472],{"class":33,"line":2471},91,[31,2473,668],{"emptyLinePlaceholder":667},[31,2475,2477,2480,2482,2485,2488,2490,2492,2495,2497,2499],{"class":33,"line":2476},92,[31,2478,2479],{"class":673},"  fp32 vy",[31,2481,776],{"class":639},[31,2483,2484],{"class":51},"0.0",[31,2486,2487],{"class":673},",vx",[31,2489,776],{"class":639},[31,2491,2484],{"class":51},[31,2493,2494],{"class":673},",vw",[31,2496,776],{"class":639},[31,2498,2484],{"class":51},[31,2500,867],{"class":673},[31,2502,2504,2507,2509,2512,2514],{"class":33,"line":2503},93,[31,2505,2506],{"class":673},"  fp32 yaw_ ",[31,2508,776],{"class":639},[31,2510,2511],{"class":51}," 0.0",[31,2513,2429],{"class":673},[31,2515,2516],{"class":261}," // 机器人航向角（单位：弧度）\n",[31,2518,2520],{"class":33,"line":2519},94,[31,2521,2522],{"class":673},"  fp32 dt_;\n",[31,2524,2526],{"class":33,"line":2525},95,[31,2527,668],{"emptyLinePlaceholder":667},[31,2529,2531,2534,2536,2538,2540],{"class":33,"line":2530},96,[31,2532,2533],{"class":673},"  fp32 x_position_ ",[31,2535,776],{"class":639},[31,2537,2511],{"class":51},[31,2539,2429],{"class":673},[31,2541,2542],{"class":261}," // x位置\n",[31,2544,2546,2549,2551,2553,2555],{"class":33,"line":2545},97,[31,2547,2548],{"class":673},"  fp32 y_position_ ",[31,2550,776],{"class":639},[31,2552,2511],{"class":51},[31,2554,2429],{"class":673},[31,2556,2557],{"class":261}," // y位置\n",[31,2559,2561],{"class":33,"line":2560},98,[31,2562,668],{"emptyLinePlaceholder":667},[31,2564,2566,2569,2572,2575],{"class":33,"line":2565},99,[31,2567,2568],{"class":639},"  void",[31,2570,2571],{"class":37}," async_receive_message",[31,2573,2574],{"class":673},"()",[31,2576,2577],{"class":261},"  //创建一个函数更方便重新调用\n",[31,2579,2581],{"class":33,"line":2580},100,[31,2582,1478],{"class":673},[31,2584,2586,2589,2592,2594,2597,2599],{"class":33,"line":2585},101,[31,2587,2588],{"class":639},"    auto",[31,2590,2591],{"class":673}," port ",[31,2593,776],{"class":639},[31,2595,2596],{"class":673}," serial_driver_->",[31,2598,1825],{"class":37},[31,2600,1578],{"class":673},[31,2602,2604],{"class":33,"line":2603},102,[31,2605,668],{"emptyLinePlaceholder":667},[31,2607,2609],{"class":33,"line":2608},103,[31,2610,2611],{"class":261},"    // 设置接收回调函数\n",[31,2613,2615,2618,2621,2624,2626,2629,2631,2633,2635,2638,2640,2643,2646,2648,2651,2653,2655,2658,2661,2664],{"class":33,"line":2614},104,[31,2616,2617],{"class":673},"    port->",[31,2619,2620],{"class":37},"async_receive",[31,2622,2623],{"class":673},"([",[31,2625,1116],{"class":51},[31,2627,2628],{"class":673},"](",[31,2630,1948],{"class":639},[31,2632,1412],{"class":37},[31,2634,744],{"class":673},[31,2636,2637],{"class":37},"vector",[31,2639,803],{"class":673},[31,2641,2642],{"class":639},"uint8_t",[31,2644,2645],{"class":673},"> ",[31,2647,1956],{"class":639},[31,2649,2650],{"class":756},"data",[31,2652,2053],{"class":673},[31,2654,1948],{"class":639},[31,2656,2657],{"class":639}," size_t",[31,2659,2660],{"class":639}," &",[31,2662,2663],{"class":756},"size",[31,2665,1211],{"class":673},[31,2667,2669],{"class":33,"line":2668},105,[31,2670,819],{"class":673},[31,2672,2674],{"class":33,"line":2673},106,[31,2675,2676],{"class":261},"      //创建odom消息类型\n",[31,2678,2680,2683,2686,2688,2690,2692,2694,2696,2698],{"class":33,"line":2679},107,[31,2681,2682],{"class":639},"      auto",[31,2684,2685],{"class":673}," odom_msg ",[31,2687,776],{"class":639},[31,2689,64],{"class":37},[31,2691,744],{"class":673},[31,2693,2040],{"class":37},[31,2695,744],{"class":673},[31,2697,2294],{"class":37},[31,2699,1578],{"class":673},[31,2701,2703],{"class":33,"line":2702},108,[31,2704,668],{"emptyLinePlaceholder":667},[31,2706,2708,2711,2714,2716,2718],{"class":33,"line":2707},109,[31,2709,2710],{"class":639},"        if",[31,2712,2713],{"class":673}," (size ",[31,2715,1204],{"class":639},[31,2717,797],{"class":51},[31,2719,760],{"class":673},[31,2721,2723],{"class":33,"line":2722},110,[31,2724,2725],{"class":673},"        {\n",[31,2727,2729,2732,2734,2736,2738,2740,2742,2744,2746,2748,2750,2753,2755],{"class":33,"line":2728},111,[31,2730,2731],{"class":639},"          for",[31,2733,750],{"class":673},[31,2735,789],{"class":639},[31,2737,792],{"class":673},[31,2739,776],{"class":639},[31,2741,797],{"class":51},[31,2743,800],{"class":673},[31,2745,803],{"class":639},[31,2747,1015],{"class":673},[31,2749,789],{"class":639},[31,2751,2752],{"class":673},")size;",[31,2754,812],{"class":639},[31,2756,2757],{"class":673},"i)\n",[31,2759,2761],{"class":33,"line":2760},112,[31,2762,2763],{"class":673},"          {\n",[31,2765,2767,2770,2773,2775],{"class":33,"line":2766},113,[31,2768,2769],{"class":639},"            uint8_t",[31,2771,2772],{"class":673}," data_buffer ",[31,2774,776],{"class":639},[31,2776,2777],{"class":673}," data[i];\n",[31,2779,2781],{"class":33,"line":2780},114,[31,2782,2783],{"class":261},"            // 处理接收到的数据\n",[31,2785,2787,2790,2793],{"class":33,"line":2786},115,[31,2788,2789],{"class":673},"            serial_pack_.rx.",[31,2791,2792],{"class":37},"Data_Analysis",[31,2794,1662],{"class":673},[31,2796,2798,2801],{"class":33,"line":2797},116,[31,2799,2800],{"class":639},"              &",[31,2802,2803],{"class":673},"data_buffer,\n",[31,2805,2807,2810,2813],{"class":33,"line":2806},117,[31,2808,2809],{"class":639},"              0x",[31,2811,2812],{"class":51},"01",[31,2814,2815],{"class":673},",\n",[31,2817,2819,2822],{"class":33,"line":2818},118,[31,2820,2821],{"class":51},"            0",[31,2823,2815],{"class":673},[31,2825,2827,2829],{"class":33,"line":2826},119,[31,2828,2821],{"class":51},[31,2830,2815],{"class":673},[31,2832,2834,2836],{"class":33,"line":2833},120,[31,2835,2821],{"class":51},[31,2837,2815],{"class":673},[31,2839,2841,2843],{"class":33,"line":2840},121,[31,2842,2821],{"class":51},[31,2844,2815],{"class":673},[31,2846,2848,2851],{"class":33,"line":2847},122,[31,2849,2850],{"class":51},"            8",[31,2852,1512],{"class":673},[31,2854,2856],{"class":33,"line":2855},123,[31,2857,2858],{"class":673},"          }\n",[31,2860,2862],{"class":33,"line":2861},124,[31,2863,2864],{"class":261},"          //由于在ROS2中，node是局部变量，所以发布方只能在node类里，故Data_Apply不写任何东西，直接在接收下面的回调函数里实现功能。\n",[31,2866,2868,2871,2874,2877,2880,2882],{"class":33,"line":2867},125,[31,2869,2870],{"class":639},"          if",[31,2872,2873],{"class":673},"(serial_pack_.rx.data.cmd ",[31,2875,2876],{"class":639},"==",[31,2878,2879],{"class":639}," 0x",[31,2881,2812],{"class":51},[31,2883,760],{"class":673},[31,2885,2887],{"class":33,"line":2886},126,[31,2888,2763],{"class":673},[31,2890,2892,2895,2897,2899,2901,2903,2905,2907,2910,2912],{"class":33,"line":2891},127,[31,2893,2894],{"class":37},"            RCLCPP_DEBUG",[31,2896,750],{"class":673},[31,2898,1116],{"class":51},[31,2900,1495],{"class":673},[31,2902,1625],{"class":37},[31,2904,1628],{"class":673},[31,2906,1880],{"class":41},[31,2908,2909],{"class":51},"\\n",[31,2911,1880],{"class":41},[31,2913,1512],{"class":673},[31,2915,2917,2919,2921,2923,2925,2927,2929,2932],{"class":33,"line":2916},128,[31,2918,2894],{"class":37},[31,2920,750],{"class":673},[31,2922,1116],{"class":51},[31,2924,1495],{"class":673},[31,2926,1625],{"class":37},[31,2928,1628],{"class":673},[31,2930,2931],{"class":41},"\"以下是电机编码器的odom数据：\"",[31,2933,1512],{"class":673},[31,2935,2937],{"class":33,"line":2936},129,[31,2938,668],{"emptyLinePlaceholder":667},[31,2940,2942,2945],{"class":33,"line":2941},130,[31,2943,2944],{"class":261},"            //",[31,2946,2947],{"class":261}," // 存储电机速度数据\n",[31,2949,2951,2954],{"class":33,"line":2950},131,[31,2952,2953],{"class":261},"            // received_encoder_wheel_velocities_[0] = serial_pack_.rx.data.fp32_buffer[0];",[31,2955,2956],{"class":261},"  // 电机 0 速度\n",[31,2958,2960,2963],{"class":33,"line":2959},132,[31,2961,2962],{"class":261},"            // received_encoder_wheel_velocities_[1] = serial_pack_.rx.data.fp32_buffer[1];",[31,2964,2965],{"class":261},"  // 电机 1 速度\n",[31,2967,2969,2972],{"class":33,"line":2968},133,[31,2970,2971],{"class":261},"            // received_encoder_wheel_velocities_[2] = serial_pack_.rx.data.fp32_buffer[2];",[31,2973,2974],{"class":261},"  // 电机 2 速度\n",[31,2976,2978,2981],{"class":33,"line":2977},134,[31,2979,2980],{"class":261},"            // received_encoder_wheel_velocities_[3] = serial_pack_.rx.data.fp32_buffer[3];",[31,2982,2983],{"class":261},"  // 电机 3 速度\n",[31,2985,2987],{"class":33,"line":2986},135,[31,2988,668],{"emptyLinePlaceholder":667},[31,2990,2992,2994],{"class":33,"line":2991},136,[31,2993,2944],{"class":261},[31,2995,2996],{"class":261}," // 存储电机位置数据\n",[31,2998,3000,3003],{"class":33,"line":2999},137,[31,3001,3002],{"class":261},"            // received_encoder_wheel_angle_[0] = serial_pack_.rx.data.fp32_buffer[4];",[31,3004,3005],{"class":261},"  // 电机 0 位置\n",[31,3007,3009,3012],{"class":33,"line":3008},138,[31,3010,3011],{"class":261},"            // received_encoder_wheel_angle_[1] = serial_pack_.rx.data.fp32_buffer[5];",[31,3013,3014],{"class":261},"  // 电机 1 位置\n",[31,3016,3018,3021],{"class":33,"line":3017},139,[31,3019,3020],{"class":261},"            // received_encoder_wheel_angle_[2] = serial_pack_.rx.data.fp32_buffer[6];",[31,3022,3023],{"class":261},"  // 电机 2 位置\n",[31,3025,3027,3030],{"class":33,"line":3026},140,[31,3028,3029],{"class":261},"            // received_encoder_wheel_angle_[3] = serial_pack_.rx.data.fp32_buffer[7];",[31,3031,3032],{"class":261},"  // 电机 3 位置\n",[31,3034,3036],{"class":33,"line":3035},141,[31,3037,668],{"emptyLinePlaceholder":667},[31,3039,3041],{"class":33,"line":3040},142,[31,3042,3043],{"class":261},"            // vx = serial_pack_.rx.data.fp32_buffer[8];\n",[31,3045,3047],{"class":33,"line":3046},143,[31,3048,3049],{"class":261},"            // vy = serial_pack_.rx.data.fp32_buffer[9];\n",[31,3051,3053],{"class":33,"line":3052},144,[31,3054,3055],{"class":261},"            // vw = serial_pack_.rx.data.fp32_buffer[10];\n",[31,3057,3059],{"class":33,"line":3058},145,[31,3060,3061],{"class":261},"            // yaw_ = serial_pack_.rx.data.fp32_buffer[11];\n",[31,3063,3065],{"class":33,"line":3064},146,[31,3066,3067],{"class":261},"            // dt_ = serial_pack_.rx.data.fp32_buffer[12];\n",[31,3069,3071],{"class":33,"line":3070},147,[31,3072,3073],{"class":261},"            // x_position_ = serial_pack_.rx.data.fp32_buffer[13];\n",[31,3075,3077],{"class":33,"line":3076},148,[31,3078,3079],{"class":261},"            // y_position_ = serial_pack_.rx.data.fp32_buffer[14];\n",[31,3081,3083],{"class":33,"line":3082},149,[31,3084,668],{"emptyLinePlaceholder":667},[31,3086,3088,3091,3093,3096,3098],{"class":33,"line":3087},150,[31,3089,3090],{"class":673},"            vx ",[31,3092,776],{"class":639},[31,3094,3095],{"class":673}," serial_pack_.rx.data.fp32_buffer[",[31,3097,898],{"class":51},[31,3099,3100],{"class":673},"];\n",[31,3102,3104,3107,3109,3111,3113],{"class":33,"line":3103},151,[31,3105,3106],{"class":673},"            vy ",[31,3108,776],{"class":639},[31,3110,3095],{"class":673},[31,3112,910],{"class":51},[31,3114,3100],{"class":673},[31,3116,3118,3121,3123,3125,3127],{"class":33,"line":3117},152,[31,3119,3120],{"class":673},"            vw ",[31,3122,776],{"class":639},[31,3124,3095],{"class":673},[31,3126,920],{"class":51},[31,3128,3100],{"class":673},[31,3130,3132,3135,3137,3139,3141],{"class":33,"line":3131},153,[31,3133,3134],{"class":673},"            yaw_ ",[31,3136,776],{"class":639},[31,3138,3095],{"class":673},[31,3140,929],{"class":51},[31,3142,3100],{"class":673},[31,3144,3146,3149,3151,3153,3156],{"class":33,"line":3145},154,[31,3147,3148],{"class":673},"            dt_ ",[31,3150,776],{"class":639},[31,3152,3095],{"class":673},[31,3154,3155],{"class":51},"4",[31,3157,3100],{"class":673},[31,3159,3161,3164,3166,3168,3171],{"class":33,"line":3160},155,[31,3162,3163],{"class":673},"            x_position_ ",[31,3165,776],{"class":639},[31,3167,3095],{"class":673},[31,3169,3170],{"class":51},"5",[31,3172,3100],{"class":673},[31,3174,3176,3179,3181,3183,3186],{"class":33,"line":3175},156,[31,3177,3178],{"class":673},"            y_position_ ",[31,3180,776],{"class":639},[31,3182,3095],{"class":673},[31,3184,3185],{"class":51},"6",[31,3187,3100],{"class":673},[31,3189,3191],{"class":33,"line":3190},157,[31,3192,668],{"emptyLinePlaceholder":667},[31,3194,3196],{"class":33,"line":3195},158,[31,3197,3198],{"class":261},"            // 打印电机速度和位置（角度）\n",[31,3200,3202,3205,3207,3210,3212,3214,3216,3219,3221,3223,3226,3228],{"class":33,"line":3201},159,[31,3203,3204],{"class":639},"            for",[31,3206,1015],{"class":673},[31,3208,3209],{"class":639},"int",[31,3211,792],{"class":673},[31,3213,776],{"class":639},[31,3215,797],{"class":51},[31,3217,3218],{"class":673},"; i ",[31,3220,803],{"class":639},[31,3222,806],{"class":51},[31,3224,3225],{"class":673},"; ",[31,3227,812],{"class":639},[31,3229,3230],{"class":673},"i) \n",[31,3232,3234],{"class":33,"line":3233},160,[31,3235,3236],{"class":673},"            {\n",[31,3238,3240],{"class":33,"line":3239},161,[31,3241,3242],{"class":261},"                // RCLCPP_DEBUG(this->get_logger(), \"%d号电机的速度: %.6f RPM, 位置: %.6f (2000pc)\",\n",[31,3244,3246],{"class":33,"line":3245},162,[31,3247,3248],{"class":261},"                //             i, received_encoder_wheel_velocities_[i], received_encoder_wheel_angle_[i]);\n",[31,3250,3252],{"class":33,"line":3251},163,[31,3253,668],{"emptyLinePlaceholder":667},[31,3255,3257,3260,3262,3264,3266,3268,3271,3274,3277,3280,3282,3285,3287,3289,3292,3294,3296],{"class":33,"line":3256},164,[31,3258,3259],{"class":37},"                RCLCPP_DEBUG",[31,3261,750],{"class":673},[31,3263,1116],{"class":51},[31,3265,1495],{"class":673},[31,3267,1625],{"class":37},[31,3269,3270],{"class":673},"(),",[31,3272,3273],{"class":41},"\"线速度:x:",[31,3275,3276],{"class":51},"%.6f",[31,3278,3279],{"class":41},",y:",[31,3281,3276],{"class":51},[31,3283,3284],{"class":41},",z:",[31,3286,3276],{"class":51},[31,3288,1880],{"class":41},[31,3290,3291],{"class":673},",vx,vy,",[31,3293,2484],{"class":51},[31,3295,843],{"class":639},[31,3297,1512],{"class":673},[31,3299,3301,3303,3305,3307,3309,3311,3313,3316,3318,3320,3322,3324,3326,3328,3330,3332,3334,3336,3338,3340],{"class":33,"line":3300},165,[31,3302,3259],{"class":37},[31,3304,750],{"class":673},[31,3306,1116],{"class":51},[31,3308,1495],{"class":673},[31,3310,1625],{"class":37},[31,3312,3270],{"class":673},[31,3314,3315],{"class":41},"\"角速度:x:",[31,3317,3276],{"class":51},[31,3319,3279],{"class":41},[31,3321,3276],{"class":51},[31,3323,3284],{"class":41},[31,3325,3276],{"class":51},[31,3327,1880],{"class":41},[31,3329,2053],{"class":673},[31,3331,2484],{"class":51},[31,3333,843],{"class":639},[31,3335,2053],{"class":673},[31,3337,2484],{"class":51},[31,3339,843],{"class":639},[31,3341,3342],{"class":673},",vw);\n",[31,3344,3346,3348,3350,3352,3354,3356,3358,3361,3363,3366,3368,3370,3372,3374,3376,3378,3380,3382,3384,3386],{"class":33,"line":3345},166,[31,3347,3259],{"class":37},[31,3349,750],{"class":673},[31,3351,1116],{"class":51},[31,3353,1495],{"class":673},[31,3355,1625],{"class":37},[31,3357,3270],{"class":673},[31,3359,3360],{"class":41},"\"欧拉角(逆正顺负):r:",[31,3362,3276],{"class":51},[31,3364,3365],{"class":41},",p:",[31,3367,3276],{"class":51},[31,3369,3279],{"class":41},[31,3371,3276],{"class":51},[31,3373,1880],{"class":41},[31,3375,2053],{"class":673},[31,3377,2484],{"class":51},[31,3379,843],{"class":639},[31,3381,2053],{"class":673},[31,3383,2484],{"class":51},[31,3385,843],{"class":639},[31,3387,3388],{"class":673},",yaw_);\n",[31,3390,3392,3394,3396,3398,3400,3402,3404,3407,3409,3411],{"class":33,"line":3391},167,[31,3393,3259],{"class":37},[31,3395,750],{"class":673},[31,3397,1116],{"class":51},[31,3399,1495],{"class":673},[31,3401,1625],{"class":37},[31,3403,3270],{"class":673},[31,3405,3406],{"class":41},"\"积分间隔:",[31,3408,3276],{"class":51},[31,3410,1880],{"class":41},[31,3412,3413],{"class":673},",dt_);\n",[31,3415,3417,3419,3421,3423,3425,3427,3429,3432,3434,3436],{"class":33,"line":3416},168,[31,3418,3259],{"class":37},[31,3420,750],{"class":673},[31,3422,1116],{"class":51},[31,3424,1495],{"class":673},[31,3426,1625],{"class":37},[31,3428,3270],{"class":673},[31,3430,3431],{"class":41},"\"右手坐标系X坐标(前正后负):",[31,3433,3276],{"class":51},[31,3435,1880],{"class":41},[31,3437,3438],{"class":673},",x_position_);\n",[31,3440,3442,3444,3446,3448,3450,3452,3454,3457,3459,3461],{"class":33,"line":3441},169,[31,3443,3259],{"class":37},[31,3445,750],{"class":673},[31,3447,1116],{"class":51},[31,3449,1495],{"class":673},[31,3451,1625],{"class":37},[31,3453,3270],{"class":673},[31,3455,3456],{"class":41},"\"右手坐标系Y坐标(左正右负):",[31,3458,3276],{"class":51},[31,3460,1880],{"class":41},[31,3462,3463],{"class":673},",y_position_);\n",[31,3465,3467],{"class":33,"line":3466},170,[31,3468,3469],{"class":673},"            }\n",[31,3471,3473],{"class":33,"line":3472},171,[31,3474,668],{"emptyLinePlaceholder":667},[31,3476,3478],{"class":33,"line":3477},172,[31,3479,3480],{"class":261},"            //时间戳\n",[31,3482,3484,3487,3489,3491,3493,3496,3498,3501],{"class":33,"line":3483},173,[31,3485,3486],{"class":673},"            odom_msg.header.stamp ",[31,3488,776],{"class":639},[31,3490,1104],{"class":51},[31,3492,1495],{"class":673},[31,3494,3495],{"class":37},"get_clock",[31,3497,1828],{"class":673},[31,3499,3500],{"class":37},"now",[31,3502,1578],{"class":673},[31,3504,3506],{"class":33,"line":3505},174,[31,3507,668],{"emptyLinePlaceholder":667},[31,3509,3511],{"class":33,"line":3510},175,[31,3512,3513],{"class":261},"            //位姿信息所参考的坐标系\n",[31,3515,3517,3520,3522,3525],{"class":33,"line":3516},176,[31,3518,3519],{"class":673},"            odom_msg.header.frame_id ",[31,3521,776],{"class":639},[31,3523,3524],{"class":41}," \"odom\"",[31,3526,867],{"class":673},[31,3528,3530],{"class":33,"line":3529},177,[31,3531,668],{"emptyLinePlaceholder":667},[31,3533,3535],{"class":33,"line":3534},178,[31,3536,3537],{"class":261},"            // 设置child_frame_id（底盘坐标系）\n",[31,3539,3541,3544,3546,3549,3551],{"class":33,"line":3540},179,[31,3542,3543],{"class":673},"            odom_msg.child_frame_id ",[31,3545,776],{"class":639},[31,3547,3548],{"class":41}," \"base_link\"",[31,3550,2429],{"class":673},[31,3552,3553],{"class":261},"  // 设置子坐标系为机器人底盘坐标系\n",[31,3555,3557],{"class":33,"line":3556},180,[31,3558,668],{"emptyLinePlaceholder":667},[31,3560,3562],{"class":33,"line":3561},181,[31,3563,3564],{"class":261},"            //DOF平动位置\n",[31,3566,3568,3571,3573],{"class":33,"line":3567},182,[31,3569,3570],{"class":673},"            odom_msg.pose.pose.position.x ",[31,3572,776],{"class":639},[31,3574,3575],{"class":673}," x_position_;\n",[31,3577,3579,3582,3584],{"class":33,"line":3578},183,[31,3580,3581],{"class":673},"            odom_msg.pose.pose.position.y ",[31,3583,776],{"class":639},[31,3585,3586],{"class":673}," y_position_;\n",[31,3588,3590,3593,3595,3597],{"class":33,"line":3589},184,[31,3591,3592],{"class":673},"            odom_msg.pose.pose.position.z ",[31,3594,776],{"class":639},[31,3596,2511],{"class":51},[31,3598,867],{"class":673},[31,3600,3602],{"class":33,"line":3601},185,[31,3603,668],{"emptyLinePlaceholder":667},[31,3605,3607],{"class":33,"line":3606},186,[31,3608,3609],{"class":261},"            //从欧拉角转换为四元数\n",[31,3611,3613,3616],{"class":33,"line":3612},187,[31,3614,3615],{"class":37},"            tf2",[31,3617,3618],{"class":673},"::Quaternion q;\n",[31,3620,3622,3625,3628,3630,3632,3634,3636],{"class":33,"line":3621},188,[31,3623,3624],{"class":673},"            q.",[31,3626,3627],{"class":37},"setRPY",[31,3629,750],{"class":673},[31,3631,898],{"class":51},[31,3633,2053],{"class":673},[31,3635,898],{"class":51},[31,3637,3388],{"class":673},[31,3639,3641],{"class":33,"line":3640},189,[31,3642,3643],{"class":261},"            //DOF转动（四元数）\n",[31,3645,3647,3650,3652,3655,3658],{"class":33,"line":3646},190,[31,3648,3649],{"class":673},"            odom_msg.pose.pose.orientation.x ",[31,3651,776],{"class":639},[31,3653,3654],{"class":673}," q.",[31,3656,3657],{"class":37},"x",[31,3659,1578],{"class":673},[31,3661,3663,3666,3668,3670,3673],{"class":33,"line":3662},191,[31,3664,3665],{"class":673},"            odom_msg.pose.pose.orientation.y ",[31,3667,776],{"class":639},[31,3669,3654],{"class":673},[31,3671,3672],{"class":37},"y",[31,3674,1578],{"class":673},[31,3676,3678,3681,3683,3685,3688],{"class":33,"line":3677},192,[31,3679,3680],{"class":673},"            odom_msg.pose.pose.orientation.z ",[31,3682,776],{"class":639},[31,3684,3654],{"class":673},[31,3686,3687],{"class":37},"z",[31,3689,1578],{"class":673},[31,3691,3693,3696,3698,3700,3703],{"class":33,"line":3692},193,[31,3694,3695],{"class":673},"            odom_msg.pose.pose.orientation.w ",[31,3697,776],{"class":639},[31,3699,3654],{"class":673},[31,3701,3702],{"class":37},"w",[31,3704,1578],{"class":673},[31,3706,3708],{"class":33,"line":3707},194,[31,3709,668],{"emptyLinePlaceholder":667},[31,3711,3713],{"class":33,"line":3712},195,[31,3714,3715],{"class":261},"            //线速度\n",[31,3717,3719,3722,3724],{"class":33,"line":3718},196,[31,3720,3721],{"class":673},"            odom_msg.twist.twist.linear.x ",[31,3723,776],{"class":639},[31,3725,3726],{"class":673}," vx;\n",[31,3728,3730,3733,3735],{"class":33,"line":3729},197,[31,3731,3732],{"class":673},"            odom_msg.twist.twist.linear.y ",[31,3734,776],{"class":639},[31,3736,3737],{"class":673}," vy;\n",[31,3739,3741,3744,3746,3748],{"class":33,"line":3740},198,[31,3742,3743],{"class":673},"            odom_msg.twist.twist.linear.z ",[31,3745,776],{"class":639},[31,3747,2511],{"class":51},[31,3749,867],{"class":673},[31,3751,3753],{"class":33,"line":3752},199,[31,3754,668],{"emptyLinePlaceholder":667},[31,3756,3758],{"class":33,"line":3757},200,[31,3759,3760],{"class":261},"            //角速度\n",[31,3762,3764,3767,3769,3771],{"class":33,"line":3763},201,[31,3765,3766],{"class":673},"            odom_msg.twist.twist.angular.x ",[31,3768,776],{"class":639},[31,3770,2511],{"class":51},[31,3772,867],{"class":673},[31,3774,3776,3779,3781,3783],{"class":33,"line":3775},202,[31,3777,3778],{"class":673},"            odom_msg.twist.twist.angular.y ",[31,3780,776],{"class":639},[31,3782,2511],{"class":51},[31,3784,867],{"class":673},[31,3786,3788,3791,3793],{"class":33,"line":3787},203,[31,3789,3790],{"class":673},"            odom_msg.twist.twist.angular.z ",[31,3792,776],{"class":639},[31,3794,3795],{"class":673}," vw;\n",[31,3797,3799],{"class":33,"line":3798},204,[31,3800,668],{"emptyLinePlaceholder":667},[31,3802,3804],{"class":33,"line":3803},205,[31,3805,3806],{"class":261},"            // 发布消息\n",[31,3808,3810,3813,3816],{"class":33,"line":3809},206,[31,3811,3812],{"class":673},"            odom_pub_->",[31,3814,3815],{"class":37},"publish",[31,3817,3818],{"class":673},"(odom_msg);\n",[31,3820,3822],{"class":33,"line":3821},207,[31,3823,668],{"emptyLinePlaceholder":667},[31,3825,3827],{"class":33,"line":3826},208,[31,3828,3829],{"class":261},"            // 打印位置（XYZ）\n",[31,3831,3833,3835],{"class":33,"line":3832},209,[31,3834,2894],{"class":37},[31,3836,1662],{"class":673},[31,3838,3840,3843,3845,3847],{"class":33,"line":3839},210,[31,3841,3842],{"class":51},"              this",[31,3844,1495],{"class":673},[31,3846,1625],{"class":37},[31,3848,3849],{"class":673},"(),\n",[31,3851,3853,3856,3858,3860,3862,3864,3866,3868],{"class":33,"line":3852},211,[31,3854,3855],{"class":41},"              \"位置Position(XYZ): ",[31,3857,3276],{"class":51},[31,3859,1506],{"class":41},[31,3861,3276],{"class":51},[31,3863,1506],{"class":41},[31,3865,3276],{"class":51},[31,3867,1880],{"class":41},[31,3869,2815],{"class":673},[31,3871,3873],{"class":33,"line":3872},212,[31,3874,3875],{"class":673},"              odom_msg.pose.pose.position.x,\n",[31,3877,3879],{"class":33,"line":3878},213,[31,3880,3881],{"class":673},"              odom_msg.pose.pose.position.y,\n",[31,3883,3885],{"class":33,"line":3884},214,[31,3886,3887],{"class":673},"              odom_msg.pose.pose.position.z\n",[31,3889,3891],{"class":33,"line":3890},215,[31,3892,3893],{"class":673},"            );\n",[31,3895,3897],{"class":33,"line":3896},216,[31,3898,668],{"emptyLinePlaceholder":667},[31,3900,3902],{"class":33,"line":3901},217,[31,3903,3904],{"class":261},"            // 打印姿态（四元数WXYZ）\n",[31,3906,3908,3910],{"class":33,"line":3907},218,[31,3909,2894],{"class":37},[31,3911,1662],{"class":673},[31,3913,3915,3917,3919,3921],{"class":33,"line":3914},219,[31,3916,3842],{"class":51},[31,3918,1495],{"class":673},[31,3920,1625],{"class":37},[31,3922,3849],{"class":673},[31,3924,3926,3929,3931,3933,3935,3937,3939,3941,3943,3945],{"class":33,"line":3925},220,[31,3927,3928],{"class":41},"              \"姿态Orientation(WXYZ): ",[31,3930,3276],{"class":51},[31,3932,1506],{"class":41},[31,3934,3276],{"class":51},[31,3936,1506],{"class":41},[31,3938,3276],{"class":51},[31,3940,1506],{"class":41},[31,3942,3276],{"class":51},[31,3944,1880],{"class":41},[31,3946,2815],{"class":673},[31,3948,3950,3953],{"class":33,"line":3949},221,[31,3951,3952],{"class":673},"              odom_msg.pose.pose.orientation.w,",[31,3954,3955],{"class":261},"  // 注意顺序：WXYZ\n",[31,3957,3959],{"class":33,"line":3958},222,[31,3960,3961],{"class":673},"              odom_msg.pose.pose.orientation.x,\n",[31,3963,3965],{"class":33,"line":3964},223,[31,3966,3967],{"class":673},"              odom_msg.pose.pose.orientation.y,\n",[31,3969,3971],{"class":33,"line":3970},224,[31,3972,3973],{"class":673},"              odom_msg.pose.pose.orientation.z\n",[31,3975,3977],{"class":33,"line":3976},225,[31,3978,3893],{"class":673},[31,3980,3982],{"class":33,"line":3981},226,[31,3983,668],{"emptyLinePlaceholder":667},[31,3985,3987],{"class":33,"line":3986},227,[31,3988,3989],{"class":261},"            // 打印姿态（欧拉角RPY）\n",[31,3991,3993,3995],{"class":33,"line":3992},228,[31,3994,2894],{"class":37},[31,3996,1662],{"class":673},[31,3998,4000,4002,4004,4006],{"class":33,"line":3999},229,[31,4001,3842],{"class":51},[31,4003,1495],{"class":673},[31,4005,1625],{"class":37},[31,4007,3849],{"class":673},[31,4009,4011,4014,4016,4018,4020,4022,4024,4026],{"class":33,"line":4010},230,[31,4012,4013],{"class":41},"              \"欧拉角Euler(RPY): ",[31,4015,3276],{"class":51},[31,4017,1506],{"class":41},[31,4019,3276],{"class":51},[31,4021,1506],{"class":41},[31,4023,3276],{"class":51},[31,4025,1880],{"class":41},[31,4027,2815],{"class":673},[31,4029,4031,4034],{"class":33,"line":4030},231,[31,4032,4033],{"class":51},"              0.0",[31,4035,2815],{"class":673},[31,4037,4039,4041],{"class":33,"line":4038},232,[31,4040,4033],{"class":51},[31,4042,2815],{"class":673},[31,4044,4046],{"class":33,"line":4045},233,[31,4047,4048],{"class":673},"              yaw_\n",[31,4050,4052],{"class":33,"line":4051},234,[31,4053,3893],{"class":673},[31,4055,4057],{"class":33,"line":4056},235,[31,4058,668],{"emptyLinePlaceholder":667},[31,4060,4062],{"class":33,"line":4061},236,[31,4063,4064],{"class":261},"            // 打印线速度（XYZ）\n",[31,4066,4068,4070],{"class":33,"line":4067},237,[31,4069,2894],{"class":37},[31,4071,1662],{"class":673},[31,4073,4075,4077,4079,4081],{"class":33,"line":4074},238,[31,4076,3842],{"class":51},[31,4078,1495],{"class":673},[31,4080,1625],{"class":37},[31,4082,3849],{"class":673},[31,4084,4086,4089,4091,4093,4095,4097,4099,4101],{"class":33,"line":4085},239,[31,4087,4088],{"class":41},"              \"线速度LinearVel(XYZ): ",[31,4090,3276],{"class":51},[31,4092,1506],{"class":41},[31,4094,3276],{"class":51},[31,4096,1506],{"class":41},[31,4098,3276],{"class":51},[31,4100,1880],{"class":41},[31,4102,2815],{"class":673},[31,4104,4106],{"class":33,"line":4105},240,[31,4107,4108],{"class":673},"              odom_msg.twist.twist.linear.x,\n",[31,4110,4112],{"class":33,"line":4111},241,[31,4113,4114],{"class":673},"              odom_msg.twist.twist.linear.y,\n",[31,4116,4118],{"class":33,"line":4117},242,[31,4119,4120],{"class":673},"              odom_msg.twist.twist.linear.z\n",[31,4122,4124],{"class":33,"line":4123},243,[31,4125,3893],{"class":673},[31,4127,4129],{"class":33,"line":4128},244,[31,4130,668],{"emptyLinePlaceholder":667},[31,4132,4134],{"class":33,"line":4133},245,[31,4135,4136],{"class":261},"            // 打印角速度（XYZ）\n",[31,4138,4140,4142],{"class":33,"line":4139},246,[31,4141,2894],{"class":37},[31,4143,1662],{"class":673},[31,4145,4147,4149,4151,4153],{"class":33,"line":4146},247,[31,4148,3842],{"class":51},[31,4150,1495],{"class":673},[31,4152,1625],{"class":37},[31,4154,3849],{"class":673},[31,4156,4158,4161,4163,4165,4167,4169,4171,4173],{"class":33,"line":4157},248,[31,4159,4160],{"class":41},"              \"角速度AngularVel(XYZ): ",[31,4162,3276],{"class":51},[31,4164,1506],{"class":41},[31,4166,3276],{"class":51},[31,4168,1506],{"class":41},[31,4170,3276],{"class":51},[31,4172,1880],{"class":41},[31,4174,2815],{"class":673},[31,4176,4178],{"class":33,"line":4177},249,[31,4179,4180],{"class":673},"              odom_msg.twist.twist.angular.x,\n",[31,4182,4184],{"class":33,"line":4183},250,[31,4185,4186],{"class":673},"              odom_msg.twist.twist.angular.y,\n",[31,4188,4190],{"class":33,"line":4189},251,[31,4191,4192],{"class":673},"              odom_msg.twist.twist.angular.z\n",[31,4194,4196],{"class":33,"line":4195},252,[31,4197,3893],{"class":673},[31,4199,4201],{"class":33,"line":4200},253,[31,4202,668],{"emptyLinePlaceholder":667},[31,4204,4206],{"class":33,"line":4205},254,[31,4207,4208],{"class":261},"            /* 接下来发布tf */\n",[31,4210,4212,4215,4218,4220,4222,4224,4226,4228,4231],{"class":33,"line":4211},255,[31,4213,4214],{"class":639},"            auto",[31,4216,4217],{"class":673}," transform ",[31,4219,776],{"class":639},[31,4221,67],{"class":37},[31,4223,744],{"class":673},[31,4225,2040],{"class":37},[31,4227,744],{"class":673},[31,4229,4230],{"class":37},"TransformStamped",[31,4232,1578],{"class":673},[31,4234,4236,4239,4241,4244],{"class":33,"line":4235},256,[31,4237,4238],{"class":673},"            transform.header.stamp ",[31,4240,776],{"class":639},[31,4242,4243],{"class":673}," odom_msg.header.stamp;",[31,4245,4246],{"class":261}," // 时间戳与odom同步\n",[31,4248,4250,4253,4255,4257],{"class":33,"line":4249},257,[31,4251,4252],{"class":673},"            transform.header.frame_id ",[31,4254,776],{"class":639},[31,4256,3524],{"class":41},[31,4258,867],{"class":673},[31,4260,4262,4265,4267,4269],{"class":33,"line":4261},258,[31,4263,4264],{"class":673},"            transform.child_frame_id ",[31,4266,776],{"class":639},[31,4268,3548],{"class":41},[31,4270,867],{"class":673},[31,4272,4274,4277,4279],{"class":33,"line":4273},259,[31,4275,4276],{"class":673},"            transform.transform.translation.x ",[31,4278,776],{"class":639},[31,4280,3575],{"class":673},[31,4282,4284,4287,4289],{"class":33,"line":4283},260,[31,4285,4286],{"class":673},"            transform.transform.translation.y ",[31,4288,776],{"class":639},[31,4290,3586],{"class":673},[31,4292,4294,4297,4299,4301],{"class":33,"line":4293},261,[31,4295,4296],{"class":673},"            transform.transform.translation.z ",[31,4298,776],{"class":639},[31,4300,2511],{"class":51},[31,4302,867],{"class":673},[31,4304,4306,4309,4311,4314],{"class":33,"line":4305},262,[31,4307,4308],{"class":673},"            transform.transform.rotation ",[31,4310,776],{"class":639},[31,4312,4313],{"class":673}," odom_msg.pose.pose.orientation;",[31,4315,4316],{"class":261}," // 复用四元数\n",[31,4318,4320,4323,4326],{"class":33,"line":4319},263,[31,4321,4322],{"class":673},"            tf_broadcaster_->",[31,4324,4325],{"class":37},"sendTransform",[31,4327,4328],{"class":673},"(transform);\n",[31,4330,4332],{"class":33,"line":4331},264,[31,4333,2858],{"class":673},[31,4335,4337],{"class":33,"line":4336},265,[31,4338,668],{"emptyLinePlaceholder":667},[31,4340,4342],{"class":33,"line":4341},266,[31,4343,4344],{"class":673},"        }\n",[31,4346,4348],{"class":33,"line":4347},267,[31,4349,4350],{"class":261},"        // 继续监听新的数据\n",[31,4352,4354,4357],{"class":33,"line":4353},268,[31,4355,4356],{"class":37},"        async_receive_message",[31,4358,1578],{"class":673},[31,4360,4362],{"class":33,"line":4361},269,[31,4363,872],{"class":673},[31,4365,4367],{"class":33,"line":4366},270,[31,4368,4369],{"class":673},"    );\n",[31,4371,4373],{"class":33,"line":4372},271,[31,4374,2206],{"class":673},[31,4376,4378],{"class":33,"line":4377},272,[31,4379,668],{"emptyLinePlaceholder":667},[31,4381,4383,4385,4388,4390,4392,4394,4396,4398,4400,4402,4404,4407],{"class":33,"line":4382},273,[31,4384,2568],{"class":639},[31,4386,4387],{"class":37}," cmd_vel_sub_callback",[31,4389,750],{"class":673},[31,4391,1948],{"class":639},[31,4393,67],{"class":37},[31,4395,744],{"class":673},[31,4397,2040],{"class":37},[31,4399,744],{"class":673},[31,4401,2345],{"class":37},[31,4403,2660],{"class":639},[31,4405,4406],{"class":756},"cmd_msg",[31,4408,760],{"class":673},[31,4410,4412],{"class":33,"line":4411},274,[31,4413,1478],{"class":673},[31,4415,4417],{"class":33,"line":4416},275,[31,4418,4419],{"class":261},"    // bool bool_buffer[] = {1, 0, 1, 0};\n",[31,4421,4423],{"class":33,"line":4422},276,[31,4424,4425],{"class":261},"    // int8_t int8_buffer[] = {0x11,0x22};\n",[31,4427,4429],{"class":33,"line":4428},277,[31,4430,4431],{"class":261},"    // int16_t int16_buffer[] = {2000,6666};\n",[31,4433,4435],{"class":33,"line":4434},278,[31,4436,4437],{"class":261},"    // int32_t int32_buffer[] = {305419896};\n",[31,4439,4441,4444,4446],{"class":33,"line":4440},279,[31,4442,4443],{"class":673},"    fp32 fp32_buffer[] ",[31,4445,776],{"class":639},[31,4447,4448],{"class":673}," {(fp32)cmd_msg.linear.x,(fp32)cmd_msg.linear.y,(fp32)cmd_msg.linear.z,\n",[31,4450,4452],{"class":33,"line":4451},280,[31,4453,4454],{"class":673},"                          (fp32)cmd_msg.angular.x,(fp32)cmd_msg.angular.y,(fp32)cmd_msg.angular.z};\n",[31,4456,4458],{"class":33,"line":4457},281,[31,4459,668],{"emptyLinePlaceholder":667},[31,4461,4463],{"class":33,"line":4462},282,[31,4464,4465],{"class":261},"    //由于ROS2中node为局部变量，所以只能在node中调用send函数，所以Serial_Transmit只负责处理data_buffer。\n",[31,4467,4469,4472,4475,4477,4480,4482],{"class":33,"line":4468},283,[31,4470,4471],{"class":673},"    serial_pack_.tx.",[31,4473,4474],{"class":37},"Data_Pack",[31,4476,750],{"class":673},[31,4478,4479],{"class":639},"0x",[31,4481,2812],{"class":51},[31,4483,4484],{"class":673},", \n",[31,4486,4488,4491,4493,4495],{"class":33,"line":4487},284,[31,4489,4490],{"class":51},"                                 nullptr",[31,4492,1506],{"class":673},[31,4494,898],{"class":51},[31,4496,2815],{"class":673},[31,4498,4500,4502,4504,4506],{"class":33,"line":4499},285,[31,4501,4490],{"class":51},[31,4503,1506],{"class":673},[31,4505,898],{"class":51},[31,4507,2815],{"class":673},[31,4509,4511,4513,4515,4517],{"class":33,"line":4510},286,[31,4512,4490],{"class":51},[31,4514,1506],{"class":673},[31,4516,898],{"class":51},[31,4518,2815],{"class":673},[31,4520,4522,4524,4526,4528],{"class":33,"line":4521},287,[31,4523,4490],{"class":51},[31,4525,1506],{"class":673},[31,4527,898],{"class":51},[31,4529,2815],{"class":673},[31,4531,4533,4536,4539,4542,4544,4547],{"class":33,"line":4532},288,[31,4534,4535],{"class":673},"                                 fp32_buffer, ",[31,4537,4538],{"class":639},"sizeof",[31,4540,4541],{"class":673},"(fp32_buffer) ",[31,4543,859],{"class":639},[31,4545,4546],{"class":639}," sizeof",[31,4548,4549],{"class":673},"(fp32));\n",[31,4551,4553],{"class":33,"line":4552},289,[31,4554,668],{"emptyLinePlaceholder":667},[31,4556,4558,4560,4562,4564,4566,4568],{"class":33,"line":4557},290,[31,4559,2588],{"class":639},[31,4561,2591],{"class":673},[31,4563,776],{"class":639},[31,4565,2596],{"class":673},[31,4567,1825],{"class":37},[31,4569,1578],{"class":673},[31,4571,4573],{"class":33,"line":4572},291,[31,4574,668],{"emptyLinePlaceholder":667},[31,4576,4578],{"class":33,"line":4577},292,[31,4579,1729],{"class":639},[31,4581,4583],{"class":33,"line":4582},293,[31,4584,819],{"class":673},[31,4586,4588,4591,4594,4596,4599,4602],{"class":33,"line":4587},294,[31,4589,4590],{"class":639},"      size_t",[31,4592,4593],{"class":673}," bytes_size ",[31,4595,776],{"class":639},[31,4597,4598],{"class":673}," port->",[31,4600,4601],{"class":37},"send",[31,4603,4604],{"class":673},"(tx_data_buffer);\n",[31,4606,4608],{"class":33,"line":4607},295,[31,4609,668],{"emptyLinePlaceholder":667},[31,4611,4613,4616,4618,4620,4622,4624,4626,4629,4631,4633,4635,4637,4639,4641,4644,4646,4649,4651,4653,4655],{"class":33,"line":4612},296,[31,4614,4615],{"class":37},"      RCLCPP_DEBUG",[31,4617,750],{"class":673},[31,4619,1116],{"class":51},[31,4621,1495],{"class":673},[31,4623,1625],{"class":37},[31,4625,1628],{"class":673},[31,4627,4628],{"class":41},"\"平动XYZ：",[31,4630,3276],{"class":51},[31,4632,2053],{"class":41},[31,4634,3276],{"class":51},[31,4636,2053],{"class":41},[31,4638,3276],{"class":51},[31,4640,1880],{"class":41},[31,4642,4643],{"class":673},", fp32_buffer[",[31,4645,898],{"class":51},[31,4647,4648],{"class":673},"],fp32_buffer[",[31,4650,910],{"class":51},[31,4652,4648],{"class":673},[31,4654,920],{"class":51},[31,4656,4657],{"class":673},"]);\n",[31,4659,4661,4663,4665,4667,4669,4671,4673,4676,4678,4680,4682,4684,4686,4688,4690,4692,4694,4696,4698,4700],{"class":33,"line":4660},297,[31,4662,4615],{"class":37},[31,4664,750],{"class":673},[31,4666,1116],{"class":51},[31,4668,1495],{"class":673},[31,4670,1625],{"class":37},[31,4672,1628],{"class":673},[31,4674,4675],{"class":41},"\"转动XYZ：",[31,4677,3276],{"class":51},[31,4679,2053],{"class":41},[31,4681,3276],{"class":51},[31,4683,2053],{"class":41},[31,4685,3276],{"class":51},[31,4687,1880],{"class":41},[31,4689,4643],{"class":673},[31,4691,929],{"class":51},[31,4693,4648],{"class":673},[31,4695,3155],{"class":51},[31,4697,4648],{"class":673},[31,4699,3170],{"class":51},[31,4701,4657],{"class":673},[31,4703,4705,4707,4709,4711,4713,4715,4717,4720,4723,4726],{"class":33,"line":4704},298,[31,4706,4615],{"class":37},[31,4708,750],{"class":673},[31,4710,1116],{"class":51},[31,4712,1495],{"class":673},[31,4714,1625],{"class":37},[31,4716,1628],{"class":673},[31,4718,4719],{"class":41},"\"(",[31,4721,4722],{"class":51},"%ld",[31,4724,4725],{"class":41}," bytes)\"",[31,4727,4728],{"class":673},", bytes_size);\n",[31,4730,4732],{"class":33,"line":4731},299,[31,4733,872],{"class":673},[31,4735,4737,4739,4741,4743,4745,4747,4749],{"class":33,"line":4736},300,[31,4738,1943],{"class":639},[31,4740,750],{"class":673},[31,4742,1948],{"class":639},[31,4744,1412],{"class":37},[31,4746,1953],{"class":673},[31,4748,1956],{"class":639},[31,4750,1959],{"class":673},[31,4752,4754],{"class":33,"line":4753},301,[31,4755,819],{"class":673},[31,4757,4759,4761,4763,4765,4767,4769,4771,4774,4776,4778,4781,4783],{"class":33,"line":4758},302,[31,4760,1968],{"class":37},[31,4762,750],{"class":673},[31,4764,1116],{"class":51},[31,4766,1495],{"class":673},[31,4768,1625],{"class":37},[31,4770,1628],{"class":673},[31,4772,4773],{"class":41},"\"Error Transmiting from serial port:",[31,4775,1877],{"class":51},[31,4777,1880],{"class":41},[31,4779,4780],{"class":673},",ex.",[31,4782,1991],{"class":37},[31,4784,1904],{"class":673},[31,4786,4788],{"class":33,"line":4787},303,[31,4789,872],{"class":673},[31,4791,4793],{"class":33,"line":4792},304,[31,4794,2206],{"class":673},[31,4796,4798],{"class":33,"line":4797},305,[31,4799,4800],{"class":673},"};\n",[31,4802,4804],{"class":33,"line":4803},306,[31,4805,668],{"emptyLinePlaceholder":667},[31,4807,4809,4811,4814,4816,4818,4821,4823,4826,4829,4832],{"class":33,"line":4808},307,[31,4810,3209],{"class":639},[31,4812,4813],{"class":37}," main",[31,4815,750],{"class":673},[31,4817,3209],{"class":639},[31,4819,4820],{"class":756}," argc",[31,4822,1506],{"class":673},[31,4824,4825],{"class":639},"char",[31,4827,4828],{"class":639}," **",[31,4830,4831],{"class":756},"argv",[31,4833,760],{"class":673},[31,4835,4837],{"class":33,"line":4836},308,[31,4838,765],{"class":673},[31,4840,4842,4844,4846,4849],{"class":33,"line":4841},309,[31,4843,2276],{"class":37},[31,4845,744],{"class":673},[31,4847,4848],{"class":37},"init",[31,4850,4851],{"class":673},"(argc, argv);\n",[31,4853,4855],{"class":33,"line":4854},310,[31,4856,668],{"emptyLinePlaceholder":667},[31,4858,4860,4863,4866,4868,4870,4872,4874,4876,4878],{"class":33,"line":4859},311,[31,4861,4862],{"class":639},"  auto",[31,4864,4865],{"class":673}," node ",[31,4867,776],{"class":639},[31,4869,1412],{"class":37},[31,4871,744],{"class":673},[31,4873,1747],{"class":37},[31,4875,803],{"class":673},[31,4877,2166],{"class":37},[31,4879,4880],{"class":673},">();\n",[31,4882,4884],{"class":33,"line":4883},312,[31,4885,668],{"emptyLinePlaceholder":667},[31,4887,4889,4891,4893,4896],{"class":33,"line":4888},313,[31,4890,2276],{"class":37},[31,4892,744],{"class":673},[31,4894,4895],{"class":37},"spin",[31,4897,4898],{"class":673},"(node);\n",[31,4900,4902],{"class":33,"line":4901},314,[31,4903,668],{"emptyLinePlaceholder":667},[31,4905,4907,4909,4911,4914],{"class":33,"line":4906},315,[31,4908,2276],{"class":37},[31,4910,744],{"class":673},[31,4912,4913],{"class":37},"shutdown",[31,4915,1578],{"class":673},[31,4917,4919,4922,4924],{"class":33,"line":4918},316,[31,4920,4921],{"class":639},"  return",[31,4923,797],{"class":51},[31,4925,867],{"class":673},[31,4927,4929],{"class":33,"line":4928},317,[31,4930,1316],{"class":673},[14,4932,4933],{},[590,4934],{"alt":26,"src":4935},"https://cdn.tungchiahui.cn/tungwebsite/assets/images/2023/12/30/image1799.webp",[14,4937,4938],{},"最終odom有效數據應該在250Hz左右,4ms發佈一次,對於導航也是完全夠用的.",[4940,4941,4942],"style",{},"html pre.shiki code .sScJk, html code.shiki .sScJk{--shiki-default:#6F42C1;--shiki-dark:#B392F0}html pre.shiki code .sZZnC, html code.shiki .sZZnC{--shiki-default:#032F62;--shiki-dark:#9ECBFF}html pre.shiki code .sj4cs, html code.shiki .sj4cs{--shiki-default:#005CC5;--shiki-dark:#79B8FF}html .default .shiki span {color: var(--shiki-default);background: var(--shiki-default-bg);font-style: var(--shiki-default-font-style);font-weight: var(--shiki-default-font-weight);text-decoration: var(--shiki-default-text-decoration);}html .shiki span {color: var(--shiki-default);background: var(--shiki-default-bg);font-style: var(--shiki-default-font-style);font-weight: var(--shiki-default-font-weight);text-decoration: var(--shiki-default-text-decoration);}html .dark .shiki span {color: var(--shiki-dark);background: var(--shiki-dark-bg);font-style: var(--shiki-dark-font-style);font-weight: var(--shiki-dark-font-weight);text-decoration: var(--shiki-dark-text-decoration);}html.dark .shiki span {color: var(--shiki-dark);background: var(--shiki-dark-bg);font-style: var(--shiki-dark-font-style);font-weight: var(--shiki-dark-font-weight);text-decoration: var(--shiki-dark-text-decoration);}html pre.shiki code .sJ8bj, html code.shiki .sJ8bj{--shiki-default:#6A737D;--shiki-dark:#6A737D}html pre.shiki code .szBVR, html code.shiki .szBVR{--shiki-default:#D73A49;--shiki-dark:#F97583}html pre.shiki code .sVt8B, html code.shiki .sVt8B{--shiki-default:#24292E;--shiki-dark:#E1E4E8}html pre.shiki code .s4XuR, html code.shiki .s4XuR{--shiki-default:#E36209;--shiki-dark:#FFAB70}",{"title":26,"searchDepth":265,"depth":265,"links":4944},[4945,4946,4947],{"id":12,"depth":277,"text":12},{"id":101,"depth":277,"text":101},{"id":579,"depth":277,"text":579},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-1-li-cheng-ji-odom","14.6.1",14060100,"2023-12-30","wiki/2023-12-30-ros2-tutorial","zh-hant:2023-12-30-ros2-tutorial","/zh-hant/wiki/2023-12-30-ros2-tutorial","Ros2 Tutorial","md","wiki/2023-12-30-ros2-tutorial/ch14-6-1-里程计Odom",false,null,"zh-Hant","zh-hant",{},{"title":5,"description":26},"/wiki/2023-12-30-ros2-tutorial/ch14-6-1-li-cheng-ji-odom","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-1-里程计Odom","SPUWuDrRsRHCiDJi151vGMDasavl9RkXT3xkmT26DLE",[4968,4973,4978,4984,4990,4996,5002,5008,5014,5020,5026,5032,5038,5044,5050,5056,5062,5068,5073,5079,5084,5090,5096,5102,5108,5114,5120,5126,5132,5138,5139,5145,5151,5157,5163,5169,5175,5181,5187,5193,5199,5205,5211,5217,5223,5229,5235,5241,5247,5253,5259,5264,5270,5275,5280,5285,5290,5296,5302,5308],{"path":4969,"stem":4970,"title":4971,"date":4951,"chapter":910,"chapterSort":4972,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch1-ros2-jie-shao","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch1-ROS2介绍","ROS2介紹",1000000,{"path":4974,"stem":4975,"title":4976,"date":4951,"chapter":2056,"chapterSort":4977,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch10-stage-ros2-fang-zhen-ping-tai","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch10-Stage_Ros2仿真平台","Stage_Ros2仿真平臺",10000000,{"path":4979,"stem":4980,"title":4981,"date":4951,"chapter":4982,"chapterSort":4983,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch11-1-gazeboclassic","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch11-1-GazeboClassic","Gezebo Classic","11.1",11010000,{"path":4985,"stem":4986,"title":4987,"date":4951,"chapter":4988,"chapterSort":4989,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch11-2-ignitiongazebo","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch11-2-IgnitionGazebo","Ignition Gazebo（Gazebo Fortress）","11.2",11020000,{"path":4991,"stem":4992,"title":4993,"date":4951,"chapter":4994,"chapterSort":4995,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch11-3-gazebosim","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch11-3-GazeboSim","Gz Sim（Gazebo Harmonic）","11.3",11030000,{"path":4997,"stem":4998,"title":4999,"date":4951,"chapter":5000,"chapterSort":5001,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch11-4-igngz2gzsim","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch11-4-Igngz2gzsim","將Ign Gazebo遷移至Gz Sim","11.4",11040000,{"path":5003,"stem":5004,"title":5005,"date":4951,"chapter":5006,"chapterSort":5007,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch11-gezebo-fang-zhen-ping-tai","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch11-Gezebo仿真平台","Gezebo仿真平臺","11",11000000,{"path":5009,"stem":5010,"title":5011,"date":4951,"chapter":5012,"chapterSort":5013,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch12-1-humble-ban-ben","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch12-1-Humble版本","Humble導航仿真","12.1",12010000,{"path":5015,"stem":5016,"title":5017,"date":4951,"chapter":5018,"chapterSort":5019,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch12-2-jazzy-ban-ben","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch12-2-Jazzy版本","Jazzy導航仿真","12.2",12020000,{"path":5021,"stem":5022,"title":5023,"date":4951,"chapter":5024,"chapterSort":5025,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch12-3-humble2jazzy","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch12-3-Humble2Jazzy","Humble與Jazzy導航的差異","12.3",12030000,{"path":5027,"stem":5028,"title":5029,"date":4951,"chapter":5030,"chapterSort":5031,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch12-ji-qi-ren-dao-hang-navigation2-fang-zhen-pian","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch12-机器人导航Navigation2(仿真篇)","機器人導航Navigation2(仿真篇)","12",12000000,{"path":5033,"stem":5034,"title":5035,"date":4951,"chapter":5036,"chapterSort":5037,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-1-1-boost-aiso","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-1-1-Boost.Aiso","Boost.Asio庫","13.1.1",13010100,{"path":5039,"stem":5040,"title":5041,"date":4951,"chapter":5042,"chapterSort":5043,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-1-2-ros2-serial-driver","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-1-2-ros2_serial_driver","ROS2 Serial Driver庫","13.1.2",13010200,{"path":5045,"stem":5046,"title":5047,"date":4951,"chapter":5048,"chapterSort":5049,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-1-chuan-kou-tong-xin","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-1-串口通信","UART串口通信","13.1",13010000,{"path":5051,"stem":5052,"title":5053,"date":4951,"chapter":5054,"chapterSort":5055,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-2-1-socketcan","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-2-1-socketcan","SocketCAN","13.2.1",13020100,{"path":5057,"stem":5058,"title":5059,"date":4951,"chapter":5060,"chapterSort":5061,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-2-2-ros2-socketcan","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-2-2-ros2_socketcan","ROS2_SocketCAN","13.2.2",13020200,{"path":5063,"stem":5064,"title":5065,"date":4951,"chapter":5066,"chapterSort":5067,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-2-can-tong-xin","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-2-CAN通信","CAN通信","13.2",13020000,{"path":5069,"stem":5070,"title":5035,"date":4951,"chapter":5071,"chapterSort":5072,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-3-1-boost-aiso","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-3-1-Boost.Aiso","13.3.1",13030100,{"path":5074,"stem":5075,"title":5076,"date":4951,"chapter":5077,"chapterSort":5078,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-3-tcp-tong-xin","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-3-TCP通信","TCP通信","13.3",13030000,{"path":5080,"stem":5081,"title":5035,"date":4951,"chapter":5082,"chapterSort":5083,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-4-1-boost-aiso","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-4-1-Boost.Aiso","13.4.1",13040100,{"path":5085,"stem":5086,"title":5087,"date":4951,"chapter":5088,"chapterSort":5089,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-4-udp-tong-xin","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-4-UDP通信","UDP通信","13.4",13040000,{"path":5091,"stem":5092,"title":5093,"date":4951,"chapter":5094,"chapterSort":5095,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-linux-ying-jian-tong-xin","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch13-Linux硬件通信","Linux硬件通信","13",13000000,{"path":5097,"stem":5098,"title":5099,"date":4951,"chapter":5100,"chapterSort":5101,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-1-ji-qi-ren-zu-cheng","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-1-机器人组成","機器人組成","14.1",14010000,{"path":5103,"stem":5104,"title":5105,"date":4951,"chapter":5106,"chapterSort":5107,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-2-1-yuan-cheng-kai-fa-ssh","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-2-1-远程开发SSH","遠程開發SSH","14.2.1",14020100,{"path":5109,"stem":5110,"title":5111,"date":4951,"chapter":5112,"chapterSort":5113,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-2-2-yuan-cheng-fang-wen-zhuo-mian","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-2-2-远程访问桌面","遠程訪問桌面","14.2.2",14020200,{"path":5115,"stem":5116,"title":5117,"date":4951,"chapter":5118,"chapterSort":5119,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-2-gong-kong-ji-zhi-yuan-cheng-kai-fa-huan-jing","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-2-工控机之远程开发环境","工控機之遠程開發環境","14.2",14020000,{"path":5121,"stem":5122,"title":5123,"date":4951,"chapter":5124,"chapterSort":5125,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-3-gong-kong-ji-zhi-wai-jie-usb-she-bei","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-3-工控机之外接USB设备","工控機之外接USB設備","14.3",14030000,{"path":5127,"stem":5128,"title":5129,"date":4951,"chapter":5130,"chapterSort":5131,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-4-fen-bu-shi-da-jian","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-4-分布式搭建","分佈式搭建","14.4",14040000,{"path":5133,"stem":5134,"title":5135,"date":4951,"chapter":5136,"chapterSort":5137,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-5-you-hua-ri-zhi","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-5-优化日志","優化日誌","14.5",14050000,{"path":4948,"stem":4965,"title":5,"date":4951,"chapter":4949,"chapterSort":4950,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},{"path":5140,"stem":5141,"title":5142,"date":4951,"chapter":5143,"chapterSort":5144,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-2-guan-xing-ji-imu","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-2-惯性计IMU","慣性計IMU","14.6.2",14060200,{"path":5146,"stem":5147,"title":5148,"date":4951,"chapter":5149,"chapterSort":5150,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-3-ji-guang-lei-da-lidar","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-3-激光雷达LiDAR","激光雷達LiDAR","14.6.3",14060300,{"path":5152,"stem":5153,"title":5154,"date":4951,"chapter":5155,"chapterSort":5156,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-4-xiang-ji-camera","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-4-相机Camera","相機Camera","14.6.4",14060400,{"path":5158,"stem":5159,"title":5160,"date":4951,"chapter":5161,"chapterSort":5162,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-5-quan-qiu-ding-wei-gnss","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-5-全球定位GNSS","全球定位GNSS","14.6.5",14060500,{"path":5164,"stem":5165,"title":5166,"date":4951,"chapter":5167,"chapterSort":5168,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-6-shou-bing-joy","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-6-手柄joy","手柄JOY","14.6.6",14060600,{"path":5170,"stem":5171,"title":5172,"date":4951,"chapter":5173,"chapterSort":5174,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-7-jian-pan-kong-zhi-jie-dian","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-7-键盘控制节点","鍵盤控制節點","14.6.7",14060700,{"path":5176,"stem":5177,"title":5178,"date":4951,"chapter":5179,"chapterSort":5180,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-ying-jian-ping-tai","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-6-硬件平台","硬件平臺","14.6",14060000,{"path":5182,"stem":5183,"title":5184,"date":4951,"chapter":5185,"chapterSort":5186,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-7-zuo-biao-xi-yu-hua-ti-guan-xi","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-7-坐标系与话题关系","座標系與話題關係","14.7",14070000,{"path":5188,"stem":5189,"title":5190,"date":4951,"chapter":5191,"chapterSort":5192,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-1-1-lun-shi-li-cheng-ji-biao-ding","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-1-1-轮式里程计标定","輪式里程計標定","14.8.1.1",14080101,{"path":5194,"stem":5195,"title":5196,"date":4951,"chapter":5197,"chapterSort":5198,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-1-2-lun-shi-li-cheng-ji-yu-imu-rong-he","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-1-2-轮式里程计与IMU融合","輪式里程計與IMU融合","14.8.1.2",14080102,{"path":5200,"stem":5201,"title":5202,"date":4951,"chapter":5203,"chapterSort":5204,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-1-lun-shi-li-cheng-ji-biao-ding-yu-rong-he","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-1-轮式里程计标定与融合","輪式里程計標定與融合","14.8.1",14080100,{"path":5206,"stem":5207,"title":5208,"date":4951,"chapter":5209,"chapterSort":5210,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-2-ji-guang-lei-da-gong-ju","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-2-激光雷达工具","激光雷達工具","14.8.2",14080200,{"path":5212,"stem":5213,"title":5214,"date":4951,"chapter":5215,"chapterSort":5216,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-3-xiang-ji-shi-yong-jin-jie","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-3-相机使用进阶","相機使用進階","14.8.3",14080300,{"path":5218,"stem":5219,"title":5220,"date":4951,"chapter":5221,"chapterSort":5222,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-ying-jian-ping-tai-jin-jie","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-8-硬件平台进阶","硬件平臺進階","14.8",14080000,{"path":5224,"stem":5225,"title":5226,"date":4951,"chapter":5227,"chapterSort":5228,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-ji-qi-ren-ying-jian","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch14-机器人硬件","機器人硬件","14",14000000,{"path":5230,"stem":5231,"title":5232,"date":4951,"chapter":5233,"chapterSort":5234,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch15-ros2-control","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch15-ROS2_Control","ROS2_Control","15",15000000,{"path":5236,"stem":5237,"title":5238,"date":4951,"chapter":5239,"chapterSort":5240,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch16-moveit2-gong-ye-ji-qi-ren-ji-xie-bi","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch16-Moveit2工业机器人机械臂","Moveit2工業機器人機械臂","16",16000000,{"path":5242,"stem":5243,"title":5244,"date":4951,"chapter":5245,"chapterSort":5246,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch17-ji-qi-ren-dao-hang-navigation2-shi-ti-pian","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch17-机器人导航Navigation2(实体篇)","機器人導航Navigation2(實體篇)","17",17000000,{"path":5248,"stem":5249,"title":5250,"date":4951,"chapter":5251,"chapterSort":5252,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch18-microros","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch18-MicroROS","MicroROS","18",18000000,{"path":5254,"stem":5255,"title":5256,"date":4951,"chapter":5257,"chapterSort":5258,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch19-webots-fang-zhen-ping-tai","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch19-Webots仿真平台","Webots仿真平臺","19",19000000,{"path":5260,"stem":5261,"title":5262,"date":4951,"chapter":920,"chapterSort":5263,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch2-ru-men-cao-zuo","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch2-入门操作","入門操作",2000000,{"path":5265,"stem":5266,"title":5267,"date":4951,"chapter":5268,"chapterSort":5269,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch20-opencv","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch20-OpenCV","OpenCV","20",20000000,{"path":5271,"stem":5272,"title":5273,"date":4951,"chapter":929,"chapterSort":5274,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch3-gong-zuo-kong-jian-yu-gong-neng-bao","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch3-工作空间与功能包","工作空間與功能包",3000000,{"path":5276,"stem":5277,"title":5278,"date":4951,"chapter":3155,"chapterSort":5279,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch4-si-da-tong-xin","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch4-四大通信","四大通信",4000000,{"path":5281,"stem":5282,"title":5283,"date":4951,"chapter":3170,"chapterSort":5284,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch5-ros2-qi-ta-tong-xin-ji-zhi","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch5-ROS2其他通信机制","ROS2其他通信機制",5000000,{"path":5286,"stem":5287,"title":5288,"date":4951,"chapter":3185,"chapterSort":5289,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch6-launch","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch6-Launch","Launch",6000000,{"path":5291,"stem":5292,"title":5293,"date":4951,"chapter":5294,"chapterSort":5295,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch7-hui-su-rosbag2","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch7-回溯rosbag2","回溯rosbag2","7",7000000,{"path":5297,"stem":5298,"title":5299,"date":4951,"chapter":5300,"chapterSort":5301,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch8-zuo-biao-bian-huan-tf","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch8-坐标变换TF","座標變換TF","8",8000000,{"path":5303,"stem":5304,"title":5305,"date":4951,"chapter":5306,"chapterSort":5307,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":4958},"/zh-hant/wiki/2023-12-30-ros2-tutorial/ch9-ke-shi-hua-ping-tai-rviz2-yu-urdf-jian-mo-yu-yan","_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/ch9-可视化平台RVIZ2与URDF建模语言","可視化平臺RVIZ2與URDF建模語言","9",9000000,{"path":4954,"stem":5309,"title":5310,"date":4951,"chapter":4959,"chapterSort":5311,"docKey":4953,"docRoot":4954,"docTitle":4955,"isWikiDoc":667,"isWikiIndex":667},"_i18n/zh-hant/wiki/2023-12-30-ros2-tutorial/index","ROS2機器人操作系統教程",0,{"variants":5313},[5314,5317,5318,5321,5324],{"path":5315,"localeSlug":5316,"i18nKey":4957},"/en-us/wiki/2023-12-30-ros2-tutorial/ch14-6-1-li-cheng-ji-odom","en-us",{"path":4948,"localeSlug":4961,"i18nKey":4957},{"path":5319,"localeSlug":5320,"i18nKey":4957},"/zh-hk/wiki/2023-12-30-ros2-tutorial/ch14-6-1-li-cheng-ji-odom","zh-hk",{"path":5322,"localeSlug":5323,"i18nKey":4957},"/zh-tw/wiki/2023-12-30-ros2-tutorial/ch14-6-1-li-cheng-ji-odom","zh-tw",{"path":5325,"localeSlug":5326,"i18nKey":4957},"/zh-cn/wiki/2023-12-30-ros2-tutorial/ch14-6-1-li-cheng-ji-odom","zh-cn",[5315,4964,4948,4964,5319,4964,5322,4964,5325,4964],1780671835963]