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

Image Publisher and Subscriber in same node.

asked 2017-04-30 10:26:10 -0500

alexandru.lesi gravatar image

I'm trying to get this code to work:

#include "ros/ros.h"
#include "std_msgs/String.h"
#include "image_transport/image_transport.h"
#include "opencv2/imgproc/imgproc.hpp"
#include "opencv2/highgui/highgui.hpp"
#include "cv_bridge/cv_bridge.h"
#include "image_geometry/pinhole_camera_model.h"

#include <sstream>

class GetRays{

private:

  image_transport::Publisher  pub;
  image_transport::Subscriber sub;

public:

  GetRays(ros::NodeHandle &nh, image_transport::ImageTransport &it){
    pub = it.advertise("/blob_map",1);
    sub = it.subscribe("/saliency_map", 1, imageCallback);
  }

  void thresholdImage(const sensor_msgs::ImageConstPtr& msg, sensor_msgs::ImageConstPtr& out){
    cv::Mat mat = cv_bridge::toCvShare(msg, "bgr8")->image;
    cv::threshold(mat,mat,0,255,3);
    out = cv_bridge::CvImage(std_msgs::Header(), "bgr8", mat).toImageMsg();
  }

  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
  {
    sensor_msgs::ImageConstPtr thresh;
    thresholdImage(msg,thresh);
    pub.publish(msg);
  }
};

int main(int argc, char **argv)
{
  ros::NodeHandle nh;
  image_transport::ImageTransport it(nh);
  ros::init(argc, argv, "get_ray");
  GetRays getRays(nh,it);
  ros::spin();

  return 0;
}

But for some reason it keeps complaining that I'm not passing the right attributes to the it.subscribe("/saliency_map", 1, imageCallback) constructor:

/disk/users/lesi/Saliency/catkin_ws/src/saliency/src/get_rays.cpp: In constructor 'GetRays::GetRays(ros::NodeHandle&, image_transport::ImageTransport&)':
/disk/users/lesi/Saliency/catkin_ws/src/saliency/src/get_rays.cpp:22:57: error: no matching function for call to 'image_transport::ImageTransport::subscribe(const char [14], int, <unresolved overloaded function type>)'
     sub = it.subscribe("/saliency_map", 1, imageCallback);
                                                         ^
/disk/users/lesi/Saliency/catkin_ws/src/saliency/src/get_rays.cpp:22:57: note: candidates are:
In file included from /disk/users/lesi/Saliency/catkin_ws/src/saliency/src/get_rays.cpp:3:0:
/opt/ros/indigo/include/image_transport/image_transport.h:74:14: note: image_transport::Subscriber image_transport::ImageTransport::subscribe(const string&, uint32_t, const boost::function<void(const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&)>&, const VoidPtr&, const image_transport::TransportHints&)
   Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
              ^
/opt/ros/indigo/include/image_transport/image_transport.h:74:14: note:   no known conversion for argument 3 from '<unresolved overloaded function type>' to 'const boost::function<void(const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&)>&'
/opt/ros/indigo/include/image_transport/image_transport.h:82:14: note: image_transport::Subscriber image_transport::ImageTransport::subscribe(const string&, uint32_t, void (*)(const ImageConstPtr&), const image_transport::TransportHints&)
   Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
              ^
/opt/ros/indigo/include/image_transport/image_transport.h:82:14: note:   no known conversion for argument 3 from '<unresolved overloaded function type>' to 'void (*)(const ImageConstPtr&) {aka void (*)(const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&)}'
/opt/ros/indigo/include/image_transport/image_transport.h:95:14: note: template<class T> image_transport::Subscriber image_transport::ImageTransport::subscribe(const string&, uint32_t, void (T::*)(const ImageConstPtr&), T*, const image_transport::TransportHints&)
   Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
              ^
/opt/ros/indigo/include/image_transport/image_transport.h:95:14: note:   template argument deduction/substitution failed:
/disk/users/lesi/Saliency/catkin_ws/src/saliency/src/get_rays.cpp:22:57: note:   candidate expects 5 arguments, 3 provided
     sub = it.subscribe("/saliency_map", 1, imageCallback);
                                                         ^
In file included from /disk/users/lesi/Saliency/catkin_ws/src/saliency/src/get_rays.cpp:3:0:
/opt/ros/indigo/include/image_transport/image_transport.h:106:14: note ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2017-04-30 14:35:10 -0500

updated 2017-04-30 16:27:58 -0500

There are a couple of comments I have.

First, you put your publisher within your callback function:

     void imageCallback(const sensor_msgs::ImageConstPtr& msg)
      {
        sensor_msgs::ImageConstPtr thresh;
       thresholdImage(msg,thresh);
        pub.publish(msg);
    }

This should not be. Try putting your subscriber in your main, before you call spin.

Secondly, you have your subscriber object in your class' constructor sub = it.subscribe("/saliency_map", 1, imageCallback); , so ros says the function object in your imageCallback method is unknown. I meant this from your traceback:

error: no matching function for call to 'image_transport::ImageTransport::subscribe(const char [14], int, <unresolved overloaded function type>)'

You can try forward declaring your imageCallback function before calling the class' constructor.

Do those two corrections and let us know what happens.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2017-04-30 10:26:10 -0500

Seen: 1,568 times

Last updated: Apr 30 '17