Learn the proper use of ROS spin for a ROS subscriber so that the data received in the callback function can be accessed. This is an answer to a question on the ROS Answers forum. Let’s go!
Related Resources
Step 1: Get your development environment ready
Either of the following will do:
- Use the ROS Development Studio (ROSDS), an online platform for developing for ROS within a PC browser. Easy-peasy. I’m using this option for this post.
- Once you log in, click on the New ROSject button to create a project that will host your code. Then Click on Open ROSject to launch the development/simulation environment.
- To open a “terminal” on ROSDS, pick the
Shell
app from the Tools menu. - You can find the
IDE
app on the Tools menu.
- You have ROS installed on a local PC. Okay, skip to Step 2.
Next step!
Step 2: Create a ROS project containing the C++ code
Create a ROS project in your workspace
user:~$ cd ~/catkin_ws/src user:~/catkin_ws/src$ catkin_create_pkg callback_fix roscpp Created file callback_fix/package.xml Created file callback_fix/CMakeLists.txt Created folder callback_fix/include/callback_fix Created folder callback_fix/src Successfully created files in /home/user/catkin_ws/src/callback_fix. Please adjust the values in package.xml.
Create a C++ file in the project’s src
folder and paste in the code specified below.
user:~/catkin_ws/src$ cd callback_fix/src user:~/catkin_ws/src/callback_fix/src$ touch callback_fix_node.cpp user:~/catkin_ws/src/callback_fix/src$
We are using a slightly modified version of the code here, using simpler message types since the driving_msg
is not available.
#include "ros/ros.h" #include "std_msgs/Int32.h" #include <iostream> using namespace std; class server { public: int totalobjects; void chatterCallback(const std_msgs::Int32 &msg); }; void server::chatterCallback(const std_msgs::Int32 &msg) { totalobjects = msg.data; } int main(int argc, char **argv) { server objserver; ros::init(argc, argv, "listener"); ros::NodeHandle n; ros::Subscriber sub = n.subscribe("/ground_truth", 1000, &server::chatterCallback, &objserver); ros::spin(); cout << objserver.totalobjects; cout << "\n"; return 0; }
On ROSDS, pick the IDE from the Tools menu, locate the callback_code.cpp
file and paste in the code.
Step 3: Prepare your C++ code for compilation and compile it
To ensure that our C++ code is runnable, we need to make some modifications to the CMakeLists.txt
file. Please edit the following Build
section of the file as follows.
We have simply uncommented the add_executable
, add_dependencies
and target_link_libraries
directives.
PS: If your C++ file is named differently, you need to adjust the values accordingly. I have used the default name for the C++ file and its, which is ${PROJECT_NAME}_node.cpp
(callback_fix_node.cpp
). It’s executable will be generated without the .cpp
suffix.
########### ## Build ## ########### ## Specify additional locations of header files ## Your package locations should be listed before other locations include_directories( # include ${catkin_INCLUDE_DIRS} ) ## Declare a C++ library # add_library(${PROJECT_NAME} # src/${PROJECT_NAME}/callback_fix.cpp # ) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries ## either from message generation or dynamic reconfigure # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) ## Declare a C++ executable ## With catkin_make all packages are built within a single CMake context ## The recommended prefix ensures that target names across packages don't collide add_executable(${PROJECT_NAME}_node src/callback_fix_node.cpp) ## Rename C++ executable without prefix ## The above recommended prefix causes long target names, the following renames the ## target back to the shorter version for ease of user use ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") ## Add cmake target dependencies of the executable ## same as for the library above add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) ## Specify libraries to link a library or executable target against target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES} )
Compile the package. Go back to the Terminal and…
user:~/catkin_ws/src/callback_fix/src$ cd ~/catkin_ws/ user:~/catkin_ws$ catkin_make
Step 4: Run your package and experience the elusive output!
user:~/catkin_ws$ rosrun callback_fix callback_fix_node
PS: If you get a message indicating a connection cannot be made to the master
, please stop the program, run nohup roscore &
to start the master
node in the background and then start your program again.
Open another terminal and publish to the ground_truth
topic. You should see the published data in the terminal where you started in the callback_fix_node
.
user:~$ rostopic pub /ground_truth std_msgs/Int32 "data: 55" publishing and latching message. Press ctrl-C to terminate
Did something happen? I’d bet it didn’t, whew!
Now stop the callback_fix_node
:
user:~/catkin_ws$ rosrun callback_fix callback_fix_node ^C55 user:~/catkin_ws$
Huh, did you see that? The moment we stopped the node, the data we published appeared. That’s baloney, isn’t it? Let’s find out the fix in the next section.
Step 5: Fix the baloney (by implementing a proper use of ROS spin) and run the program again
In the callback_fix_node.cpp
file, we can see that the print statements appear right after then ros::spin()
statement! The problem is, anything after ros::spin()
will not run until the program exits, because ros::spin()
creates a loop that won’t exit until the program is interrupted!
In the v2
of the code below, use ros::spinOnce()
, instead of ros::spin()
to solve the problem:
1. Replace the int main()
function with this snippet:
int main(int argc, char **argv) { server objserver; ros::init(argc, argv, "listener"); ros::NodeHandle n; ros::Rate loop_rate(1); ros::Subscriber sub = n.subscribe("/ground_truth", 1000, &server::chatterCallback, &objserver); while (ros::ok()) { ros::spinOnce(); loop_rate.sleep(); cout << objserver.totalobjects; cout << "\n"; } return 0; }
2. Compile the workspace again:
user:~/catkin_ws$ catkin_make
3. Run the callback_fix_node
again:
user:~/catkin_ws$ rosrun callback_fix callback_fix_node
4. In the other terminal, publish to the ground_truth
topic again and watch the output of the first terminal:
user:~$ rostopic pub /ground_truth std_msgs/Int32 "data: 67" publishing and latching message. Press ctrl-C to terminate
Now you should see the published data printed in the first terminal, in real-time. Try publishing other integers:
# ... 67 67 999 999 999 #...
And that was it! I hope you have learned something about the proper use of ROS spin. See you in another post!
Extra: Video of this post
We made a video showing how we solved this challenge. If you prefer “sights and sounds” to “black and white”, here you go:
Feedback
Did you like this post? Do you have any questions about the explanations? Whatever the case, please leave a comment on the comments section below, so we can interact and learn from each other.
If you want to learn about other ROS or ROS2 topics, please let us know in the comments area and we will do a video or post about it.
? Subscribe for more free ROS learning
Edited by Bayode Aderinola
0 Comments