# ROS spin 詳細解說 ROS 裡面不只有 spin() & spinOnce() 可以使用,此篇對各種 spin 的 function 功能差異詳細解說 主要可以分成 Single-Thread(單執行緒) 與 Multi-Thread(多執行緒) ### Single-Thread - ```ros::spin()``` - 程式停在本行,在node被終止才會return。只有在呼叫到該API時才開始執行callback function ```cpp= int main(int argc, char **argv){ ros::init(argc, argv, "node_name"); ros::NodeHandle n; ros::Subscriber sub = n.subscribe("topic", 1000, D); A(); B(); //假設在執行其他行程式碼的時候收到/topic送來的message C(); ros::spin(); //在呼叫這行的時候才會執行上面已經定義的callback function D() return 0; } ``` Result : ``` A B C D D D D .....``` - ```ros::spinOnce()```: 只執行一次,可避免 race condition, 也是在呼叫到該API時才執行callback function - 需包在 ```while()``` 中使用 ```cpp= int main(int argc, char **argv){ ros::init(argc, argv, "node_name"); ros::NodeHandle n; ros::Subscriber sub = n.subscribe("topic", 1000, D); while(ros::ok()){ A(); B(); C(); ros::spinOnce(); } return 0; } ``` Result: ``` A B C D A B C D .... ``` --- ### Multi-Thread - ```ros::MultiThreadSpinner()``` : - 似 ```ros::spin()``` 會停在本行 - 但 Single Thread 未必能保證時效性 - ex: 若在其中一個 callback 中執行較久,可能會影響到其他 callback - Reference: https://zhuanlan.zhihu.com/p/375418691 ```cpp= #include <thread> #include "ros/ros.h" #include "std_msgs/String.h" void CallbackA(const std_msgs::String::ConstPtr &msg) { // let callback sleep (似 callback 中執行較多, operation 卡在 callback 中) std::this_thread::sleep_for(std::chrono::seconds(2)); ROS_INFO(" I heard: [%s]", msg->data.c_str()); } void CallbackB(const std_msgs::String::ConstPtr &msg) { ROS_INFO(" I heard: [%s]", msg->data.c_str()); } int main(int argc, char **argv) { ros::init(argc, argv, "listener"); ros::NodeHandle n; ros::Subscriber sub_b = n.subscribe("B/message", 1, CallbackB); ros::Subscriber sub_a = n.subscribe("A/message", 1, CallbackA); // set number of threads ros::MultiThreadedSpinner spinner(2); spinner.spin(); return 0; } ``` Result: (可知 CallbackB 不會被 CallbackA 的 sleep 影響) ``` [ INFO] [1621390946.100496300]: I heard: [/B/message 1] [ INFO] [1621390947.100450900]: I heard: [/B/message 2] [ INFO] [1621390948.015270200]: I heard: [/A/message 1] [ INFO] [1621390948.099850900]: I heard: [/B/message 3] [ INFO] [1621390949.100118400]: I heard: [/B/message 4] [ INFO] [1621390950.015475900]: I heard: [/A/message 3] [ INFO] [1621390950.100807500]: I heard: [/B/message 5] [ INFO] [1621390951.100232500]: I heard: [/B/message 6] [ INFO] [1621390952.015688200]: I heard: [/A/message 5] ``` - ```ros::AsyncSpinner()```: - each callback will get its own thread (if available) - code will not be blocked - Description: - ```ros::AsyncSpinner spinner(0);``` create spinner, and designate thread number (0: use as many threads as processors) - ```spinner.start();``` start the spinner (runs in background) and program continues - ```ros::waitForShutdown();``` AsyncSpinner won't block, will wait for the node to be killed Example1: ```cpp= int main(int argc, char **argv) { ros::init(argc, argv, "talker_subscribers"); ros::NodeHandle nh; ros::AsyncSpinner spinner(0); spinner.start(); ros::Subscriber counter1_sub = nh.subscribe("talker1", 10, callbackTalker1); ros::Subscriber counter2_sub = nh.subscribe("talker2", 10, callbackTalker2); ros::waitForShutdown(); // ros::spin(); --> we don't use that anymore } ``` Example 2: ```cpp= #include "ros/ros.h" #include "ros/callback_queue.h" #include "std_msgs/Int64.h" ros::CallbackQueue queue_1; ros::CallbackQueue queue_2; void callBack_1(const std_msgs::Int64::ConstPtr& msg){ std::cout<<"1Get: "<<msg->data<<std::endl; ros::Duration(3).sleep(); } void callBack_2(const std_msgs::Int64::ConstPtr& msg){ std::cout<<"2Get: "<<msg->data<<std::endl; } void callBack_3(const std_msgs::Int64::ConstPtr& msg){ std::cout<<"3Get: "<<msg->data<<std::endl; } int main(int argc, char** argv){ ros::init(argc, argv, "MultiThread"); ros::NodeHandle nh("~"); nh.setCallbackQueue(&queue_1); ros::Subscriber sub_1 = nh.subscribe("Call1", 1, &callBack_1); ros::Subscriber sub_3 = nh.subscribe("Call3", 1, &callBack_3); nh.setCallbackQueue(&queue_2); ros::Subscriber sub_2 = nh.subscribe("Call2", 1, &callBack_2); std::cout<<"Running: "<<std::endl; ros::AsyncSpinner spinner_1(1, &queue_1); spinner_1.start(); ros::AsyncSpinner spinner_2(1, &queue_2); spinner_2.start(); ros::waitForShutdown(); } ``` >Note: > - queue_1 負責 callBack_1 和 callBack_3 > - queue_2 負責 callBack_2 > - 如果把 ros::AsyncSpinner spinner_1(1, &queue_1); 中的 1 換成 2,代表使用兩個 thread 處理 callBack_1 和 callBack_3,就不會 block --- 講解不錯的 Reference: https://roboticsbackend.com/ros-asyncspinner-example/