📖
Wiki
Back to my personal website
  • Home
  • Equipment and Devices
    • 3D Printer
    • Laser Cutter
    • Motion Capture System
    • Sensors
      • RGB-D Cameras
      • Velodyne LiDAR
      • Zed Camera
      • RealSense D435i
      • IMU
    • eGPU
    • Nvidia AGX Xavier
    • CPU Benchmark
    • Installation Checklist
  • Development
    • Linux
      • Shell
      • GDB
      • Git
      • Tmux
      • Network
      • Tricks
      • Debug FAQ
    • CMake
      • Catkin Tools
      • CMakeLists
      • CMake Variables
      • CMake Commands
      • CMake: find_package()
    • ROS
      • Gazebo
      • wstool
      • roslaunch
      • rosbag
      • multi-threaded spinner
    • ROS2
      • Convert ROS1 bag to ROS2 bag
    • C++
      • C++ 11
      • C++ Examples
      • C++ Debug
      • Factory Method
      • Timing
    • Google Tools
      • GLog
      • GFlags
      • GTest
      • Style Guide
      • Clang Format
    • PCL
      • Point Type
      • Methods
      • Architecture
      • Code Explained
    • Open3D
      • Python API
      • Registration
      • Visualization
      • Tools
    • OpenCV
      • Documentation
      • Modules
    • Other Libraries
      • Eigen
      • Ceres
      • g2o
      • GTSAM
    • Website
  • Algorithm
    • SLAM
      • K-D Tree
      • Octree
      • Bag of Words
      • Distance Measures
      • Coordinate Systems
      • LOAM
      • Iterative Closest Point
      • Generalized ICP
      • Mahalanobis Distance
    • Computer Science
      • Computational Model
      • Sorting
      • Analysis
      • Complexity Classes (P, NP)
      • Divide and Conquer
      • Greedy Algorithm
      • Dynamic Programming
      • Tree
      • Graph
    • Computer Vision
      • Camera Models
      • Distortion
      • Motion Models
      • Shutter
      • Image Sensors
      • Epipolar Geometry
      • Multiple-View Geometry
    • Datasets
      • RGB-D Datasets
      • Point Cloud Datasets
      • LiDAR SLAM Datasets
  • Math
    • Optimization
      • Convex Optimization
      • Descent Methods
    • Probability
      • Moment
      • Covariance Matrix
      • Stochastic Process
    • Topology
      • References
      • Concepts
      • Topological Spaces
      • Representation of Rotations
      • Representation of 3-sphere
    • Algebra
      • Linear Algebra
      • Matrix Factorization
      • Condition Number
      • Matrix Lie Group
    • Differential Geometry
      • Manifold
      • Submanifold
      • Quotient Manifolds
      • Tangent Space
  • Quadrotor
    • PX4 Development
    • Companion Computer
    • Drone Hardware
    • Propeller Lock
    • Debug
  • Favorites
    • Bookmarks
Powered by GitBook
On this page
  • Application Scenario
  • Solution One: MultiThreadedSpinner
  • Solution Two: AsyncSpinner

Was this helpful?

  1. Development
  2. ROS

multi-threaded spinner

Application Scenario

  • Suppose that we have two callbacks (talker1 and talker2) running at 1Hz in the same ros node. The talker2 callback can be blocked if the talker1 callback takes more than 1s. Because ros::spin() is single-threaded.

  • Note: this issue only happens with roscpp. The rospy spinner is already multi-threaded, so you won’t be able to reproduce this issue if you translate the cpp subscriber node to Python.

Solution One: MultiThreadedSpinner

  • Blocking method. Simply just increase the number of threads to process callback queues.

ros::MultiThreadedSpinner spinner(4); // Use 4 threads; or 0 to use all threads
spinner.spin(); // spin() will not return until the node has been shutdown

Solution Two: AsyncSpinner

  • Non-blocking method. Try to get each callback a thread if available.

int main(int argc, char **argv) {
    ros::init(argc, argv, "talker_subscribers");
    ros::NodeHandle nh;
    ros::AsyncSpinner spinner(0); // 0 means max number of threads available
    spinner.start();  // start the AsyncSpinner asynchronously (non-blocking)
    ros::Subscriber counter1_sub = nh.subscribe("talker1", 10, callbackTalker1);
    ros::Subscriber counter2_sub = nh.subscribe("talker2", 10, callbackTalker2);
    ros::waitForShutdown(); // block the program; wait for the node to be killed
    // alternatively, you may have an infinite loop here to process some data
}

PreviousrosbagNextROS2

Last updated 3 years ago

Was this helpful?

References: ; ;

http://wiki.ros.org/roscpp/Overview/Callbacks%20and%20Spinning
https://roboticsbackend.com/ros-asyncspinner-example
https://levelup.gitconnected.com/ros-spinning-threading-queuing-aac9c0a793f