From 3b720a2682015eeb769643f89641a54c5169a572 Mon Sep 17 00:00:00 2001
From: Johannes Mey <johannes.mey@tu-dresden.de>
Date: Tue, 1 Sep 2020 12:47:56 +0200
Subject: [PATCH] add some comments

---
 src/listener.cpp | 10 ++++++++--
 src/talker.cpp   | 12 ++++++++++++
 2 files changed, 20 insertions(+), 2 deletions(-)

diff --git a/src/listener.cpp b/src/listener.cpp
index 0c60b11..6ac2396 100644
--- a/src/listener.cpp
+++ b/src/listener.cpp
@@ -4,6 +4,11 @@
 /**
  * This tutorial demonstrates simple receipt of messages over the ROS system.
  */
+
+/**
+ * This callback function is called when a message on the topic "chatter" is received
+ * @param msg The received message
+ */
 void chatterCallback(const std_msgs::String::ConstPtr& msg)
 {
   ROS_INFO("I heard: [%s]", msg->data.c_str());
@@ -26,7 +31,8 @@ int main(int argc, char **argv)
   /**
    * NodeHandle is the main access point to communications with the ROS system.
    * The first NodeHandle constructed will fully initialize this node, and the last
-   * NodeHandle destructed will close down the node.
+   * NodeHandle destructed will close down the node. The NodeHandle can be initialized
+   * with a namespace, which is relevant for the parameter server.
    */
   ros::NodeHandle n;
 
@@ -50,7 +56,7 @@ int main(int argc, char **argv)
   /**
    * ros::spin() will enter a loop, pumping callbacks.  With this version, all
    * callbacks will be called from within this thread (the main one).  ros::spin()
-   * will exit when Ctrl-C is pressed, or the node is shutdown by the master.
+   * will exit when Ctrl-C is pressed, or the node is shut down by the master.
    */
   ros::spin();
 
diff --git a/src/talker.cpp b/src/talker.cpp
index 9cf75a9..a6fd3be 100644
--- a/src/talker.cpp
+++ b/src/talker.cpp
@@ -53,6 +53,10 @@ int main(int argc, char **argv)
    * a unique string for each message.
    */
   int count = 0;
+
+  /**
+   * The main loop runs until the ros core is shutting down.
+   */
   while (ros::ok())
   {
     /**
@@ -74,9 +78,17 @@ int main(int argc, char **argv)
      */
     chatter_pub.publish(msg);
 
+    /**
+     * The spinOnce() method processes callbacks.
+     */
     ros::spinOnce();
 
+    /**
+     * To prevent too many messages being sent and busy waiting, we sleep for some time here (the rate is 10hz,
+     * so we sleep for 100ms).
+     */
     loop_rate.sleep();
+
     ++count;
   }
 
-- 
GitLab