From 2ef240b9a7f99c19122f17d5ceb05d0f7da4d279 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 01:48:10 -0400 Subject: [PATCH 01/20] Added header file for class Talker --- include/beginner_tutorials/talker.hpp | 51 +++++++++++++++++++++++++++ 1 file changed, 51 insertions(+) create mode 100644 include/beginner_tutorials/talker.hpp diff --git a/include/beginner_tutorials/talker.hpp b/include/beginner_tutorials/talker.hpp new file mode 100644 index 0000000..8482a5e --- /dev/null +++ b/include/beginner_tutorials/talker.hpp @@ -0,0 +1,51 @@ +/** + * @file talker.hpp + * @author Sakshi Kakde + * @brief A class to publish string data on a topic + * @version 0.1 + * @date 2021-10-31 + * + * @copyright Copyright (c) 2021 + * + */ +#ifndef INCLUDE_BEGINNER_TUTORIALS_TALKER_HPP_ +#define INCLUDE_BEGINNER_TUTORIALS_TALKER_HPP_ + +#include +#include +#include +#include + +class Talker { + public: + /** + * @brief Construct a new Talker object + * + */ + Talker(); + /** + * @brief Destroy the Talker object + * + */ + ~Talker(); + /** + * @brief Runs the ros::ok loop and publishes data at a predefined rate + * + */ + void runNode(); + ros::NodeHandle* nh_p; // nodehandle + private: + std::string publisher_topic_name; // ROS publisher topic name + ros::Publisher chatter_pub; // ROS publisher object + /** + * @brief Function to init params + * + */ + void initParams(); + /** + * @brief Function to init publishers + * + */ + void initPublishers(); +}; +#endif // INCLUDE_BEGINNER_TUTORIALS_TALKER_HPP_ From c3f5928e8e50d68520679f1c7093b787b9780991 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 01:48:21 -0400 Subject: [PATCH 02/20] Implemented class Talker --- src/listener.cpp | 30 ++++++++++++++++++++---------- 1 file changed, 20 insertions(+), 10 deletions(-) diff --git a/src/listener.cpp b/src/listener.cpp index e76ee5f..11d9015 100644 --- a/src/listener.cpp +++ b/src/listener.cpp @@ -1,16 +1,26 @@ -#include "ros/ros.h" -#include "std_msgs/String.h" - /** - * This tutorial demonstrates simple receipt of messages over the ROS system. + * @file talker.cpp + * @author Sakshi Kakde + * @brief This tutorial demonstrates simple receipt of messages over the ROS system. + * @version 0.1 + * @date 2021-10-31 + * + * @copyright Copyright (c) 2021 + * + */ +#include +#include +#include +/** + * @brief + * + * @param msg */ -void chatterCallback(const std_msgs::String::ConstPtr& msg) -{ - ROS_INFO("I heard: [%s]", msg->data.c_str()); +void chatterCallback(const std_msgs::String::ConstPtr& msg) { + ROS_INFO("Yes, I heard [%s]", msg->data.c_str()); } -int main(int argc, char **argv) -{ +int main(int argc, char **argv) { /** * The ros::init() function needs to see argc and argv so that it can perform * any ROS arguments and name remapping that were provided at the command line. @@ -55,4 +65,4 @@ int main(int argc, char **argv) ros::spin(); return 0; -} \ No newline at end of file +} From fe0c309593ff50530cdb2cde2f1f99e805a49e34 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 01:48:58 -0400 Subject: [PATCH 03/20] Deleted listner.cpp --- src/listener.cpp | 68 ------------------------------------------------ 1 file changed, 68 deletions(-) delete mode 100644 src/listener.cpp diff --git a/src/listener.cpp b/src/listener.cpp deleted file mode 100644 index 11d9015..0000000 --- a/src/listener.cpp +++ /dev/null @@ -1,68 +0,0 @@ -/** - * @file talker.cpp - * @author Sakshi Kakde - * @brief This tutorial demonstrates simple receipt of messages over the ROS system. - * @version 0.1 - * @date 2021-10-31 - * - * @copyright Copyright (c) 2021 - * - */ -#include -#include -#include -/** - * @brief - * - * @param msg - */ -void chatterCallback(const std_msgs::String::ConstPtr& msg) { - ROS_INFO("Yes, I heard [%s]", msg->data.c_str()); -} - -int main(int argc, char **argv) { - /** - * The ros::init() function needs to see argc and argv so that it can perform - * any ROS arguments and name remapping that were provided at the command line. - * For programmatic remappings you can use a different version of init() which takes - * remappings directly, but for most command-line programs, passing argc and argv is - * the easiest way to do it. The third argument to init() is the name of the node. - * - * You must call one of the versions of ros::init() before using any other - * part of the ROS system. - */ - ros::init(argc, argv, "listener"); - - /** - * 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. - */ - ros::NodeHandle n; - - /** - * The subscribe() call is how you tell ROS that you want to receive messages - * on a given topic. This invokes a call to the ROS - * master node, which keeps a registry of who is publishing and who - * is subscribing. Messages are passed to a callback function, here - * called chatterCallback. subscribe() returns a Subscriber object that you - * must hold on to until you want to unsubscribe. When all copies of the Subscriber - * object go out of scope, this callback will automatically be unsubscribed from - * this topic. - * - * The second parameter to the subscribe() function is the size of the message - * queue. If messages are arriving faster than they are being processed, this - * is the number of messages that will be buffered up before beginning to throw - * away the oldest ones. - */ - ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback); - - /** - * 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. - */ - ros::spin(); - - return 0; -} From 1f9b60b1768269f8d3602c951446e29ad3359ea9 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 01:49:16 -0400 Subject: [PATCH 04/20] Implemented class Talker --- src/talker.cpp | 97 +++++++++++++++----------------------------------- 1 file changed, 29 insertions(+), 68 deletions(-) diff --git a/src/talker.cpp b/src/talker.cpp index 29537f4..09676e9 100644 --- a/src/talker.cpp +++ b/src/talker.cpp @@ -1,85 +1,46 @@ -#include "ros/ros.h" -#include "std_msgs/String.h" - -#include - /** - * This tutorial demonstrates simple sending of messages over the ROS system. + * @file talker.cpp + * @author Sakshi Kakde + * @brief A class to publish string data on a topic + * @version 0.1 + * @date 2021-10-31 + * + * @copyright Copyright (c) 2021 + * */ -int main(int argc, char **argv) -{ - /** - * The ros::init() function needs to see argc and argv so that it can perform - * any ROS arguments and name remapping that were provided at the command line. - * For programmatic remappings you can use a different version of init() which takes - * remappings directly, but for most command-line programs, passing argc and argv is - * the easiest way to do it. The third argument to init() is the name of the node. - * - * You must call one of the versions of ros::init() before using any other - * part of the ROS system. - */ - ros::init(argc, argv, "talker"); +#include - /** - * 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. - */ - ros::NodeHandle n; +Talker::Talker() { + this->nh_p = new ros::NodeHandle("~"); + initParams(); + initPublishers(); +} - /** - * The advertise() function is how you tell ROS that you want to - * publish on a given topic name. This invokes a call to the ROS - * master node, which keeps a registry of who is publishing and who - * is subscribing. After this advertise() call is made, the master - * node will notify anyone who is trying to subscribe to this topic name, - * and they will in turn negotiate a peer-to-peer connection with this - * node. advertise() returns a Publisher object which allows you to - * publish messages on that topic through a call to publish(). Once - * all copies of the returned Publisher object are destroyed, the topic - * will be automatically unadvertised. - * - * The second parameter to advertise() is the size of the message queue - * used for publishing messages. If messages are published more quickly - * than we can send them, the number here specifies how many messages to - * buffer up before throwing some away. - */ - ros::Publisher chatter_pub = n.advertise("chatter", 1000); +Talker::~Talker() +{} - ros::Rate loop_rate(10); +void Talker::initParams() { + this->nh_p->param("publisher_topic_name", this->publisher_topic_name, "/chatter"); +} - /** - * A count of how many messages we have sent. This is used to create - * a unique string for each message. - */ +void Talker::initPublishers() { + this->chatter_pub = this->nh_p->advertise(this->publisher_topic_name, 10, this); +} + +void Talker::runNode() { int count = 0; - while (ros::ok()) - { - /** - * This is a message object. You stuff it with data, and then publish it. - */ + ros::Rate loop_rate(10); + while (ros::ok()) { std_msgs::String msg; - std::stringstream ss; - ss << "hello world " << count; + ss << "Can you hear " << count << " ?"; msg.data = ss.str(); ROS_INFO("%s", msg.data.c_str()); - - /** - * The publish() function is how you send messages. The parameter - * is the message object. The type of this object must agree with the type - * given as a template parameter to the advertise<>() call, as was done - * in the constructor above. - */ - chatter_pub.publish(msg); + this->chatter_pub.publish(msg); ros::spinOnce(); - loop_rate.sleep(); ++count; } - - - return 0; -} \ No newline at end of file +} From f25d714fd14e9c8f3c3fc8ec85108882c5694573 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 01:49:40 -0400 Subject: [PATCH 05/20] Called publisher --- src/talker_node.cpp | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) create mode 100644 src/talker_node.cpp diff --git a/src/talker_node.cpp b/src/talker_node.cpp new file mode 100644 index 0000000..124773a --- /dev/null +++ b/src/talker_node.cpp @@ -0,0 +1,18 @@ +/** + * @file talker_node.cpp + * @author Sakshi Kakde + * @brief Code to publish string data on a topic + * @version 0.1 + * @date 2021-10-31 + * + * @copyright Copyright (c) 2021 + * + */ +#include + +int main(int argc, char **argv) { + ros::init(argc, argv, "talker_node"); + Talker talker; + talker.runNode(); + return 0; +} From 1ba7e6365090687537d095e00004cb2d05d5df05 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 01:49:54 -0400 Subject: [PATCH 06/20] Updated CMakelist as per new files --- CMakeLists.txt | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 79d9593..8ffbe4a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,16 +2,18 @@ cmake_minimum_required(VERSION 2.8.3) project(beginner_tutorials) ## Find catkin and any catkin packages -find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs genmsg) +find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs) ## Declare a catkin package -catkin_package() +catkin_package( + INCLUDE_DIRS include +) ## Build talker and listener include_directories(include ${catkin_INCLUDE_DIRS}) -add_executable(talker src/talker.cpp) +add_executable(talker src/talker.cpp src/talker_node.cpp) target_link_libraries(talker ${catkin_LIBRARIES}) -add_executable(listener src/listener.cpp) -target_link_libraries(listener ${catkin_LIBRARIES}) +# add_executable(listener src/listener.cpp) +# target_link_libraries(listener ${catkin_LIBRARIES}) From ee24cd863eeec1e4bbc95a78b6e3eb7f638468cb Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 01:51:43 -0400 Subject: [PATCH 07/20] Added publisher rate as ROS param --- include/beginner_tutorials/talker.hpp | 1 + src/talker.cpp | 3 ++- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/include/beginner_tutorials/talker.hpp b/include/beginner_tutorials/talker.hpp index 8482a5e..c936c97 100644 --- a/include/beginner_tutorials/talker.hpp +++ b/include/beginner_tutorials/talker.hpp @@ -37,6 +37,7 @@ class Talker { private: std::string publisher_topic_name; // ROS publisher topic name ros::Publisher chatter_pub; // ROS publisher object + int publisher_rate; // rate of publishing /** * @brief Function to init params * diff --git a/src/talker.cpp b/src/talker.cpp index 09676e9..de32850 100644 --- a/src/talker.cpp +++ b/src/talker.cpp @@ -21,10 +21,11 @@ Talker::~Talker() void Talker::initParams() { this->nh_p->param("publisher_topic_name", this->publisher_topic_name, "/chatter"); + this->nh_p->param("publisher_rate", this->publisher_rate, 10); } void Talker::initPublishers() { - this->chatter_pub = this->nh_p->advertise(this->publisher_topic_name, 10, this); + this->chatter_pub = this->nh_p->advertise(this->publisher_topic_name, this->publisher_rate, this); } void Talker::runNode() { From 07b1b2d9320e5b3a90a95bbca7dbb653fad9d412 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 01:52:42 -0400 Subject: [PATCH 08/20] cpplint error --- include/beginner_tutorials/talker.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/include/beginner_tutorials/talker.hpp b/include/beginner_tutorials/talker.hpp index c936c97..560bdff 100644 --- a/include/beginner_tutorials/talker.hpp +++ b/include/beginner_tutorials/talker.hpp @@ -34,6 +34,7 @@ class Talker { */ void runNode(); ros::NodeHandle* nh_p; // nodehandle + private: std::string publisher_topic_name; // ROS publisher topic name ros::Publisher chatter_pub; // ROS publisher object From dd62ea48c395562cbf4c80bdfaecee2980345668 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 02:07:28 -0400 Subject: [PATCH 09/20] Created header file for class Listener --- include/beginner_tutorials/listener.hpp | 58 +++++++++++++++++++++++++ 1 file changed, 58 insertions(+) create mode 100644 include/beginner_tutorials/listener.hpp diff --git a/include/beginner_tutorials/listener.hpp b/include/beginner_tutorials/listener.hpp new file mode 100644 index 0000000..0c2820b --- /dev/null +++ b/include/beginner_tutorials/listener.hpp @@ -0,0 +1,58 @@ +/** + * @file listener.hpp + * @author Sakshi Kakde + * @brief A class to subscribe to a topic of type string + * @version 0.1 + * @date 2021-10-31 + * + * @copyright Copyright (c) 2021 + * + */ +#ifndef INCLUDE_BEGINNER_TUTORIALS_LISTENER_HPP_ +#define INCLUDE_BEGINNER_TUTORIALS_LISTENER_HPP_ + +#include +#include +#include +#include + +class Listener { + public: + /** + * @brief Construct a new Listener object + * + */ + Listener(); + /** + * @brief Destroy the Listener object + * + */ + ~Listener(); + /** + * @brief waits for publisher to publish + * + */ + void runNode(); + ros::NodeHandle* nh_p; // nodehandle + + private: + std::string subscriber_topic_name; // ROS subscriber topic name + ros::Subscriber chatter_sub; // ROS Subscriber object + /** + * @brief Function to init params + * + */ + void initParams(); + /** + * @brief Function to init subscribers + * + */ + void initSubscribers(); + /** + * @brief Callback function for subscriber + * + * @param msg Message received from publisher + */ + void chatter_callback(const std_msgs::String::ConstPtr& msg); +}; +#endif // INCLUDE_BEGINNER_TUTORIALS_LISTENER_HPP_ From 5c720a76eec96f58a6408fd0c4193b3d849a55c9 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 02:07:40 -0400 Subject: [PATCH 10/20] Implemented class Listener --- src/listener.cpp | 36 ++++++++++++++++++++++++++++++++++++ 1 file changed, 36 insertions(+) create mode 100644 src/listener.cpp diff --git a/src/listener.cpp b/src/listener.cpp new file mode 100644 index 0000000..2cc76d8 --- /dev/null +++ b/src/listener.cpp @@ -0,0 +1,36 @@ +/** + * @file listener.cpp + * @author Sakshi Kakde + * @brief A class to subscribe to a topic of type string + * @version 0.1 + * @date 2021-10-31 + * + * @copyright Copyright (c) 2021 + * + */ +#include + +Listener::Listener() { + this->nh_p = new ros::NodeHandle("~"); + initParams(); + initSubscribers(); +} + +Listener::~Listener() +{} + +void Listener::initParams() { + this->nh_p->param("subscriber_topic_name", this->subscriber_topic_name, "/chatter"); +} + +void Listener::initSubscribers() { + this->chatter_sub = this->nh_p->subscribe(this->subscriber_topic_name, 1, &Listener::chatter_callback, this); +} + +void Listener::chatter_callback(const std_msgs::String::ConstPtr& msg) { + ROS_INFO("Yes, I heard [%s]", msg->data.c_str()); +} + +void Listener::runNode() { + ros::spin(); +} From 4d6e18ed4c902d0470b60ba7cd249fe91c23da76 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 02:07:55 -0400 Subject: [PATCH 11/20] Called the subscriber --- src/listener_node.cpp | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) create mode 100644 src/listener_node.cpp diff --git a/src/listener_node.cpp b/src/listener_node.cpp new file mode 100644 index 0000000..cfae283 --- /dev/null +++ b/src/listener_node.cpp @@ -0,0 +1,18 @@ +/** + * @file listener_node.cpp + * @author Sakshi Kakde + * @brief Code to subscibe to a topic + * @version 0.1 + * @date 2021-10-31 + * + * @copyright Copyright (c) 2021 + * + */ +#include + +int main(int argc, char **argv) { + ros::init(argc, argv, "listener_node"); + Listener listener; + listener.runNode(); + return 0; +} From 03b3fa93681028973bd566c66e0ad5f063776eab Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 02:08:13 -0400 Subject: [PATCH 12/20] Modified CMakelist to add the subscriber --- CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8ffbe4a..40614cd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -15,5 +15,5 @@ include_directories(include ${catkin_INCLUDE_DIRS}) add_executable(talker src/talker.cpp src/talker_node.cpp) target_link_libraries(talker ${catkin_LIBRARIES}) -# add_executable(listener src/listener.cpp) -# target_link_libraries(listener ${catkin_LIBRARIES}) +add_executable(listener src/listener.cpp src/listener_node.cpp) +target_link_libraries(listener ${catkin_LIBRARIES}) From 2c044fd66103a0d3361ca9d691cac767e6895d07 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 02:23:33 -0400 Subject: [PATCH 13/20] resolved cpplint issues --- src/listener.cpp | 6 ++++-- src/talker.cpp | 10 +++++++--- 2 files changed, 11 insertions(+), 5 deletions(-) diff --git a/src/listener.cpp b/src/listener.cpp index 2cc76d8..492867d 100644 --- a/src/listener.cpp +++ b/src/listener.cpp @@ -20,11 +20,13 @@ Listener::~Listener() {} void Listener::initParams() { - this->nh_p->param("subscriber_topic_name", this->subscriber_topic_name, "/chatter"); + this->nh_p->param("subscriber_topic_name", + this->subscriber_topic_name, "/chatter"); } void Listener::initSubscribers() { - this->chatter_sub = this->nh_p->subscribe(this->subscriber_topic_name, 1, &Listener::chatter_callback, this); + this->chatter_sub = this->nh_p->subscribe(this->subscriber_topic_name, + 1, &Listener::chatter_callback, this); } void Listener::chatter_callback(const std_msgs::String::ConstPtr& msg) { diff --git a/src/talker.cpp b/src/talker.cpp index de32850..6a601e2 100644 --- a/src/talker.cpp +++ b/src/talker.cpp @@ -20,12 +20,16 @@ Talker::~Talker() {} void Talker::initParams() { - this->nh_p->param("publisher_topic_name", this->publisher_topic_name, "/chatter"); - this->nh_p->param("publisher_rate", this->publisher_rate, 10); + this->nh_p->param("publisher_topic_name", + this->publisher_topic_name, "/chatter"); + this->nh_p->param("publisher_rate", + this->publisher_rate, 10); } void Talker::initPublishers() { - this->chatter_pub = this->nh_p->advertise(this->publisher_topic_name, this->publisher_rate, this); + this->chatter_pub = this->nh_p->advertise( + this->publisher_topic_name, + this->publisher_rate, this); } void Talker::runNode() { From 84d011053ceefc0d20c1cd6550b2a20b8a56b9ec Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 02:23:48 -0400 Subject: [PATCH 14/20] scripts to runn cpplint and cppcheck --- run_cppcheck.sh | 2 ++ run_cpplint.sh | 2 ++ 2 files changed, 4 insertions(+) create mode 100755 run_cppcheck.sh create mode 100755 run_cpplint.sh diff --git a/run_cppcheck.sh b/run_cppcheck.sh new file mode 100755 index 0000000..38fbd45 --- /dev/null +++ b/run_cppcheck.sh @@ -0,0 +1,2 @@ +cppcheck --enable=all --std=c++11 -I include/ --suppress=missingIncludeSystem $( find . -name *.cpp | grep -vE -e "^./build/" -e "^./vendor/") --output-file=results/cppcheck_process.txt > results/cppcheck_result.txt +echo "Done Processing. Results are stored in results/cppcheck_process.txt, results/cppcheck_result.txt" \ No newline at end of file diff --git a/run_cpplint.sh b/run_cpplint.sh new file mode 100755 index 0000000..60ea738 --- /dev/null +++ b/run_cpplint.sh @@ -0,0 +1,2 @@ +cpplint $( find . -name *.cpp | grep -vE -e "^./build/" -e "^./vendor/") $( find . -name *.hpp | grep -vE -e "^./build/" -e "^./vendor/") > results/cpplint_result.txt +echo "Done Processing. Results are stored in results/cpplint_result.txt" \ No newline at end of file From a48669eea3eeb15cb6bbc504dbadda93a24f1f76 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 02:24:01 -0400 Subject: [PATCH 15/20] output of cppcheck and cpplint --- results/cppcheck_process.txt | 3 +++ results/cppcheck_result.txt | 8 ++++++++ results/cpplint_result.txt | 6 ++++++ 3 files changed, 17 insertions(+) create mode 100644 results/cppcheck_process.txt create mode 100644 results/cppcheck_result.txt create mode 100644 results/cpplint_result.txt diff --git a/results/cppcheck_process.txt b/results/cppcheck_process.txt new file mode 100644 index 0000000..8c24d0e --- /dev/null +++ b/results/cppcheck_process.txt @@ -0,0 +1,3 @@ +[include/beginner_tutorials/listener.hpp:19]: (style) class 'Listener' does not have a copy constructor which is recommended since the class contains a pointer to allocated memory. +[src/talker.cpp:13]: (warning) Member variable 'Talker::publisher_rate' is not initialized in the constructor. +[include/beginner_tutorials/talker.hpp:19]: (style) class 'Talker' does not have a copy constructor which is recommended since the class contains a pointer to allocated memory. diff --git a/results/cppcheck_result.txt b/results/cppcheck_result.txt new file mode 100644 index 0000000..82f9e83 --- /dev/null +++ b/results/cppcheck_result.txt @@ -0,0 +1,8 @@ +Checking src/listener.cpp ... +1/4 files checked 31% done +Checking src/listener_node.cpp ... +2/4 files checked 45% done +Checking src/talker.cpp ... +3/4 files checked 86% done +Checking src/talker_node.cpp ... +4/4 files checked 100% done diff --git a/results/cpplint_result.txt b/results/cpplint_result.txt new file mode 100644 index 0000000..f003973 --- /dev/null +++ b/results/cpplint_result.txt @@ -0,0 +1,6 @@ +Done processing ./include/beginner_tutorials/listener.hpp +Done processing ./include/beginner_tutorials/talker.hpp +Done processing ./src/listener.cpp +Done processing ./src/listener_node.cpp +Done processing ./src/talker.cpp +Done processing ./src/talker_node.cpp From c11dab89dcd9a506acbb6c12fecf8a1d7d08ede0 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 02:29:40 -0400 Subject: [PATCH 16/20] cpplint issues --- src/listener.cpp | 4 ++-- src/talker.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/listener.cpp b/src/listener.cpp index 492867d..bb56ba2 100644 --- a/src/listener.cpp +++ b/src/listener.cpp @@ -16,8 +16,8 @@ Listener::Listener() { initSubscribers(); } -Listener::~Listener() -{} +Listener::~Listener() { +} void Listener::initParams() { this->nh_p->param("subscriber_topic_name", diff --git a/src/talker.cpp b/src/talker.cpp index 6a601e2..ece49d0 100644 --- a/src/talker.cpp +++ b/src/talker.cpp @@ -16,8 +16,8 @@ Talker::Talker() { initPublishers(); } -Talker::~Talker() -{} +Talker::~Talker() { +} void Talker::initParams() { this->nh_p->param("publisher_topic_name", From 095a232756eb7aa2bb9ba74afd2be912c4265251 Mon Sep 17 00:00:00 2001 From: sakshikakde Date: Sun, 31 Oct 2021 02:29:51 -0400 Subject: [PATCH 17/20] cppcheck outputs --- results/cppcheck_process.txt | 4 +++- results/cppcheck_result.txt | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/results/cppcheck_process.txt b/results/cppcheck_process.txt index 8c24d0e..192c8ee 100644 --- a/results/cppcheck_process.txt +++ b/results/cppcheck_process.txt @@ -1,3 +1,5 @@ [include/beginner_tutorials/listener.hpp:19]: (style) class 'Listener' does not have a copy constructor which is recommended since the class contains a pointer to allocated memory. [src/talker.cpp:13]: (warning) Member variable 'Talker::publisher_rate' is not initialized in the constructor. -[include/beginner_tutorials/talker.hpp:19]: (style) class 'Talker' does not have a copy constructor which is recommended since the class contains a pointer to allocated memory. +[src/talker.cpp:19]: (warning) Member variable 'Talker::publisher_rate' is not initialized in the constructor. +[src/talker.cpp:20]: (style) Value of pointer 'nh_p', which points to allocated memory, is copied in copy constructor instead of allocating new memory. +[include/beginner_tutorials/talker.hpp:19]: (warning) The class 'Talker' has 'copy constructor' but lack of 'operator='. diff --git a/results/cppcheck_result.txt b/results/cppcheck_result.txt index 82f9e83..7f16d18 100644 --- a/results/cppcheck_result.txt +++ b/results/cppcheck_result.txt @@ -1,7 +1,7 @@ Checking src/listener.cpp ... 1/4 files checked 31% done Checking src/listener_node.cpp ... -2/4 files checked 45% done +2/4 files checked 44% done Checking src/talker.cpp ... 3/4 files checked 86% done Checking src/talker_node.cpp ... From fd9b48a68030bbe32d8cb365016b32123e7894c7 Mon Sep 17 00:00:00 2001 From: Sakshi Kakde Date: Sun, 31 Oct 2021 02:39:45 -0400 Subject: [PATCH 18/20] Update README.md --- README.md | 39 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 39 insertions(+) diff --git a/README.md b/README.md index f0e5e13..a2927e6 100644 --- a/README.md +++ b/README.md @@ -1 +1,40 @@ # beginner_tutorials +## Introduction +This repository provides a simple example to run ROS publisher and sibscriber + +## File Structure +- include +-- listener.hpp +-- talker.hpp + +- src +-- listener.cpp +-- talker.cpp +-- listener_node.cpp +-- talker_node.cpp + +listener_node.cpp and talker_node.cpp are the files where the objectes for the classes Listener and Talker are created. + +## Building the package +1) Create a catkin workspace catkin_ws +2) Clone the package inside catkin_ws/src using +'git clone https://github.com/sakshikakde/beginner_tutorials.git' +4) cd catkin_ws +5) run +'catkin build' + +## How to run the code +1) Change the directory +'cd catkin_ws' +2)Source the workspace +'sourcedevel/setup.bash' +3) In a terminal, run 'roscore'. +4) In a new terminal, run the talker by using +'rosrun beginner_tutorials talker' +5) In a new terminal, run the listener by using +'rosrun beginner_tutorials listener' + + + + + From 4d2132a11e0c70caaead3b94e38ab66d4f3a2f7a Mon Sep 17 00:00:00 2001 From: Sakshi Kakde Date: Sun, 31 Oct 2021 02:43:24 -0400 Subject: [PATCH 19/20] Update README.md --- README.md | 44 +++++++++++++++++++++++++++++++++++--------- 1 file changed, 35 insertions(+), 9 deletions(-) diff --git a/README.md b/README.md index a2927e6..11a2242 100644 --- a/README.md +++ b/README.md @@ -18,21 +18,47 @@ listener_node.cpp and talker_node.cpp are the files where the objectes for the c ## Building the package 1) Create a catkin workspace catkin_ws 2) Clone the package inside catkin_ws/src using -'git clone https://github.com/sakshikakde/beginner_tutorials.git' -4) cd catkin_ws + +``` +git clone https://github.com/sakshikakde/beginner_tutorials.git +``` +4) Change the directory +``` +cd catkin_ws + +``` 5) run -'catkin build' + +``` +catkin build +``` ## How to run the code 1) Change the directory -'cd catkin_ws' + +``` +cd catkin_ws + +``` 2)Source the workspace -'sourcedevel/setup.bash' -3) In a terminal, run 'roscore'. -4) In a new terminal, run the talker by using -'rosrun beginner_tutorials talker' + +``` +sourcedevel/setup.bash +``` +3) In a terminal, run +``` +roscore +```. +5) In a new terminal, run the talker by using + +``` +rosrun beginner_tutorials talker + +``` 5) In a new terminal, run the listener by using -'rosrun beginner_tutorials listener' +``` +rosrun beginner_tutorials listener +``` From ea4fa4c6cd9a89186342a60320b4ff1715e7e1f2 Mon Sep 17 00:00:00 2001 From: Sakshi Kakde Date: Sun, 31 Oct 2021 02:44:17 -0400 Subject: [PATCH 20/20] Update README.md --- README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 11a2242..0b6f1a3 100644 --- a/README.md +++ b/README.md @@ -48,7 +48,7 @@ sourcedevel/setup.bash 3) In a terminal, run ``` roscore -```. +``` 5) In a new terminal, run the talker by using ``` @@ -64,3 +64,4 @@ rosrun beginner_tutorials listener +