ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How declare ROS subscriber inside a class?

asked 2022-10-07 14:18:17 -0600

Nagarjun gravatar image

updated 2022-10-08 03:53:46 -0600

ravijoshi gravatar image

I am publishing images to another node and while publishing I am also subscribing a string. When that string is true I will save the image of the published data at that moment. I am having some trouble because of the following error: no match operator '=' for the subscriber which I don't understand why.

/home/rrcam/catkin_ws/src/image_pub/src/im_pub_sub.cpp: In constructor ‘Node::Node()’:
/home/rrcam/catkin_ws/src/image_pub/src/im_pub_sub.cpp:47:73: error: no match for ‘operator=’ (operand types are ‘image_transport::Subscriber’ and ‘ros::Subscriber’)
             sub = nh_.subscribe("/chatter",1, &Node::imageCallback, this);
                                                                         ^
In file included from /opt/ros/melodic/include/image_transport/image_transport.h:39:0,
                 from /home/rrcam/catkin_ws/src/image_pub/src/im_pub_sub.cpp:2:
/opt/ros/melodic/include/image_transport/subscriber.h:61:7: note: candidate: image_transport::Subscriber& image_transport::Subscriber::operator=(const image_transport::Subscriber&)
 class Subscriber
       ^~~~~~~~~~
/opt/ros/melodic/include/image_transport/subscriber.h:61:7: note:   no known conversion for argument 1 from ‘ros::Subscriber’ to ‘const image_transport::Subscriber&’
/opt/ros/melodic/include/image_transport/subscriber.h:61:7: note: candidate: image_transport::Subscriber& image_transport::Subscriber::operator=(image_transport::Subscriber&&)
/opt/ros/melodic/include/image_transport/subscriber.h:61:7: note:   no known conversion for argument 1 from ‘ros::Subscriber’ to ‘image_transport::Subscriber&&’
image_pub/CMakeFiles/i_pub_sub.dir/build.make:62: recipe for target 'image_pub/CMakeFiles/i_pub_sub.dir/src/im_pub_sub.cpp.o' failed
make[2]: *** [image_pub/CMakeFiles/i_pub_sub.dir/src/im_pub_sub.cpp.o] Error 1
CMakeFiles/Makefile2:1521: recipe for target 'image_pub/CMakeFiles/i_pub_sub.dir/all' failed
make[1]: *** [image_pub/CMakeFiles/i_pub_sub.dir/all] Error 2
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

The Script is as follows: I don't get it what's wrong. I have also tried using boost::bind for binding this pointer and msg in subscriber callback function:

#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <opencv2/highgui/highgui.hpp>
#include <ros/ros.h>
#include <sensor_msgs/image_encodings.h>
#include <exception>
#include <iostream>
#include <opencv2/imgcodecs.hpp>
#include "std_msgs/String.h"

class Node{

    public:
        cv::Mat frame1;
        std::string GSpipeline1 = "nvarguscamerasrc sensor-id=0 ee-mode=0 ! video/x-raw(memory:NVMM), format=(string)NV12 ! nvvidconv ! video/x-raw, format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR ! appsink";
        int count =0;
        ros::NodeHandle nh_;
        ros::Rate loop_rate =10;
        cv::VideoCapture cap1;
        sensor_msgs::ImagePtr msg1;
        image_transport::ImageTransport it;
        image_transport::Publisher pub_frame1;
        image_transport::Subscriber sub;

    public:
        Node():it(nh_),cap1(GSpipeline1, cv::CAP_GSTREAMER){
            if (!cap1.isOpened())
            {
                std::cout << "Failed to open camera1." << std::endl;
                return;
            }
            pub_frame1 = it.advertise("/cam1",1);

            // sub = it.subscribe("/chatter",1, boost::bind(&Node::imageCallback, this));
            sub = nh_.subscribe("/chatter",1, &Node::imageCallback, this);
        }

        ~Node(){

        }

        void imageCallback(const std_msgs::String::ConstPtr& msg)
        {
            std::cout<<"I am here"<<std::endl;
            if(msg->data.getData() == 'true'){
                this->count++;
                cv::imwrite("/home/rrcam/sensor0/img_"+ std::to_string(this->count)+".png",this->frame1);
            }

        }

        void start(){

            while (this->nh_.ok()) {
                this->cap1 >> this->frame1;
                // this->cap1.read(this->frame1);
                if (this->frame1.empty()) {
                    ROS_ERROR_STREAM("Failed to capture1 image!");
                    ros::shutdown();
                    break;
                }
                int k = cv::waitKey(20) & 0xff ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2022-10-08 03:51:41 -0600

ravijoshi gravatar image

updated 2022-10-08 03:55:36 -0600

There are many problems with the code. Please spend some time going through it line by line.

  1. You are subscribing to string data. However, the subscriber is defined using image_transport::Subscriber, which is incompatible with string data. In summary, we should use the ros::Subscriber.
  2. You are trying to perform a string comparison. However, the RHS value is defined as 'true'. A string must be defined using double quotes such as "true". At present, RHS is nothing but an integer value.
  3. The msg->data is a string. You do not need to call getData() on it. In fact, I don't think that we have getData() in the string class. However, we do have c_str(), but we don't need c_str() for string comparison.
  4. For some reason, you are not calling ros::spinOnce() inside the while loop. It should be called periodically.
  5. We do not need ros::spinOnce() inside main function.

I am having a hard time understanding the design of the code. For example:

  1. Why are we making string comparisons?
  2. Why do we perform IO operations like writing an image inside a callback?

The code may have conceptual issues. Nevertheless, I fixed the compilation errors. Please see the complete code below:

#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <ros/ros.h>
#include <sensor_msgs/image_encodings.h>
#include <std_msgs/String.h>

#include <iostream>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgcodecs.hpp>

class Node
{
public:
  cv::Mat frame1;
  std::string GSpipeline1 =
      "nvarguscamerasrc sensor-id=0 ee-mode=0 ! video/x-raw(memory:NVMM), "
      "format=(string)NV12 ! nvvidconv ! "
      "video/x-raw, format=(string)BGRx ! videoconvert ! video/x-raw, "
      "format=(string)BGR ! appsink";
  int count = 0;
  ros::NodeHandle nh_;
  ros::Rate loop_rate = 10;
  cv::VideoCapture cap1;
  sensor_msgs::ImagePtr msg1;
  image_transport::ImageTransport it;
  image_transport::Publisher pub_frame1;
  ros::Subscriber sub;

public:
  Node() : it(nh_), cap1(GSpipeline1, cv::CAP_GSTREAMER)
  {
    if (!cap1.isOpened())
    {
      std::cout << "Failed to open camera1." << std::endl;
      return;
    }
    pub_frame1 = it.advertise("/cam1", 1);
    sub = nh_.subscribe("/chatter", 1, &Node::imageCallback, this);
  }

  ~Node()
  {
  }

  void imageCallback(const std_msgs::String::ConstPtr& msg)
  {
    std::cout << "I am here" << std::endl;
    if (msg->data == "true")
    {
      this->count++;
      cv::imwrite("/home/rrcam/sensor0/img_" + std::to_string(this->count) + ".png", this->frame1);
    }
  }

  void start()
  {
    while (this->nh_.ok())
    {
      this->cap1 >> this->frame1;
      if (this->frame1.empty())
      {
        ROS_ERROR_STREAM("Failed to capture1 image!");
        ros::shutdown();
        break;
      }
      int k = cv::waitKey(20) & 0xff;
      if (k == 27)
      {
        ROS_ERROR_STREAM("I am trying to close it");
        ros::shutdown();
        break;
      }
      this->msg1 = cv_bridge::CvImage(std_msgs::Header(), "bgr8", this->frame1).toImageMsg();
      this->pub_frame1.publish(msg1);

      ros::spinOnce();
      this->loop_rate.sleep();
    }

    if (!this->nh_.ok())
    {
      std::cout << "trouble with ros node" << std::endl;
      this->cap1.release();
    }
  }
};

int main(int argc, char** argv)
{
  ros::init(argc, argv, "im_sub_pub_cpp");
  Node n;
  n.start();
}

On a side note, please feel free to look at the various documentation such as "Writing a Simple Publisher and Subscriber (C++)", and "Writing a Simple Image Publisher (C++)".

edit flag offensive delete link more

Comments

Thank you for pointing out my mistakes @ravijoshi.

1) Yes I have changed the image_transport::Subscriber sub to ros::Subscriber sub, it works 2) We do need ROS::Spinonce, so that callback of subscriber is called.

Overall I have corrected my mistakes as you have provided the solution and the code is working. Thank you for your time.

Nagarjun gravatar image Nagarjun  ( 2022-10-13 10:00:52 -0600 )edit

I am glad you made it work. Thank you for the update. By the way, as your question is answered, may I request you to click on the checkmark i.e., ✔icon at the top left side of this answer? It will basically mark the question as answered.

ravijoshi gravatar image ravijoshi  ( 2022-10-14 02:24:37 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2022-10-07 14:18:17 -0600

Seen: 122 times

Last updated: Oct 13 '22