Robotics StackExchange | Archived questions

Calling a publisher inside a subscriber

I've been trying to follow this answer for writing a publisher inside a subscriber callback function. My code looks like the following:

class TowelThrower{
   public:
    ros::NodeHandle node_handle;
    ros::Publisher new_coors_pub;
    ros::Subscriber vision_sub;

    TowelThrower()
    {
    ros::Publisher new_coors_pub = node_handle.advertise<std_msgs::String>("coords_requests", 1000);
    ros::Subscriber vision_sub = node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
    }

    std::vector<geometry_msgs::Pose> create_path(double coorx, double coory)
    {
      std::vector<geometry_msgs::Pose> waypoints;
      return waypoints;
    }

  void callback(const geometry_msgs::Pose msg)
  {
    std_msgs::String nsg;
    nsg.data = "GIVE";

    ROS_INFO("%s", nsg.data.c_str());

    new_coors_pub.publish(nsg);
  }
};

int main(int argc, char** argv)
{
  ros::init(argc, argv, "towel_thrower_node");
  ros::AsyncSpinner spinner(1);
  spinner.start();

  ros::Rate loop_rate(10);
  //ros::spin();
  ros::shutdown();
  return 0;
}

but I am getting the following error:

/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp: In constructor ‘TowelThrower::TowelThrower()’:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: error: no matching function for call to ‘ros::NodeHandle::subscribe(const char [13], void (TowelThrower::*)(geometry_msgs::Pose), TowelThrower*)’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:402:14: note: candidate: template<class M, class T> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(M), T*, const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:402:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:413:14: note: candidate: template<class M, class T> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(M) const, T*, const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:413:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:465:14: note: candidate: template<class M, class T> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(const boost::shared_ptr<const M>&), T*, const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:465:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:475:14: note: candidate: template<class M, class T> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(const boost::shared_ptr<const M>&) const, T*, const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:475:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:529:14: note: candidate: template<class M, class T> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(M), const boost::shared_ptr<U>&, const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:529:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:540:14: note: candidate: template<class M, class T> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(M) const, const boost::shared_ptr<U>&, const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:540:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:594:14: note: candidate: template<class M, class T> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(const boost::shared_ptr<const M>&), const boost::shared_ptr<U>&, const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:594:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:605:14: note: candidate: template<class M, class T> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(const boost::shared_ptr<const M>&) const, const boost::shared_ptr<U>&, const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:605:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:656:14: note: candidate: template<class M> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (*)(M), const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:656:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:704:14: note: candidate: template<class M> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (*)(const boost::shared_ptr<const M>&), const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:704:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:750:14: note: candidate: template<class M> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, const boost::function<void(const boost::shared_ptr<const M>&)>&, const VoidConstPtr&, const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:750:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:799:14: note: candidate: template<class M, class C> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, const boost::function<void(C)>&, const VoidConstPtr&, const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size,
              ^
/opt/ros/kinetic/include/ros/node_handle.h:799:14: note: template argument deduction/substitution failed:
/home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:74:101: note:   cannot convert ‘&TowelThrower::callback’ (type ‘void (TowelThrower::*)(geometry_msgs::Pose) {aka void (TowelThrower::*)(geometry_msgs::Pose_<std::allocator<void> >)}’) to type ‘uint32_t {aka unsigned int}’
  node_handle.subscribe("vision_coors", &TowelThrower::callback, this);
                                                                     ^
In file included from /opt/ros/kinetic/include/ros/ros.h:45:0,
                 from /opt/ros/kinetic/include/urdf/model.h:47,
                 from /opt/ros/kinetic/include/moveit/robot_model/robot_model.h:43,
                 from /opt/ros/kinetic/include/moveit/robot_state/robot_state.h:41,
                 from /opt/ros/kinetic/include/moveit/planning_scene_interface/planning_scene_interface.h:41,
                 from /home/team-sewts/catkin_ws/src/towel_thrower/src/towel_thrower.cpp:38:
/opt/ros/kinetic/include/ros/node_handle.h:836:14: note: candidate: ros::Subscriber ros::NodeHandle::subscribe(ros::SubscribeOptions&)
   Subscriber subscribe(SubscribeOptions& ops);
              ^
/opt/ros/kinetic/include/ros/node_handle.h:836:14: note: candidate expects 1 argument, 3 provided
towel_thrower/CMakeFiles/towel_thrower_node.dir/build.make:62: recipe for target 'towel_thrower/CMakeFiles/towel_thrower_node.dir/src/towel_thrower.cpp.o' failed
make[2]: *** [towel_thrower/CMakeFiles/towel_thrower_node.dir/src/towel_thrower.cpp.o] Error 1
CMakeFiles/Makefile2:9419: recipe for target 'towel_thrower/CMakeFiles/towel_thrower_node.dir/all' failed
make[1]: *** [towel_thrower/CMakeFiles/towel_thrower_node.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j12 -l12" failed

Can anyone point out the error in my structure?

Asked by shu on 2019-12-19 11:25:40 UTC

Comments

Answers

Here is a solution to your problem:

#include <ros/ros.h>
#include <std_msgs/String.h>
#include <geometry_msgs/Pose.h>
#include <vector>

class TowelThrower{
    public:

    TowelThrower()
    {
        new_coors_pub = node_handle.advertise<std_msgs::String>("coords_requests", 1000);
        vision_sub = node_handle.subscribe("vision_coors", 1, &TowelThrower::callback, this);
    }

    private:

    ros::NodeHandle node_handle;
    ros::Publisher  new_coors_pub;
    ros::Subscriber vision_sub;

    std::vector<geometry_msgs::Pose> create_path(double coorx, double coory)
    {
        std::vector<geometry_msgs::Pose> waypoints;
        return waypoints;
    }

    void callback(const geometry_msgs::Pose msg)
    {
        std_msgs::String nsg;
        nsg.data = "GIVE";

        ROS_INFO("%s", nsg.data.c_str());

        new_coors_pub.publish(nsg);
    }
};

int main(int argc, char** argv)
{
    ros::init(argc, argv, "towel_thrower_node");
    TowelThrower tt;

    ros::spin();

    return 0;
}

There are number of problems with your original code:

  1. The compiler problem you are referencing is in the subscriber. You did not specify a queue size for parameter 2.
  2. It would have been good to include the header file to make this compile.
  3. The new_coords_pub and vision_sub are member variables but you also declared variable with the same the names in the constructor so the constructor will use the constructor declared variables which go out of scope when the constructor finishes.
  4. You did not declare an instance of the TowelThrower class.
  5. Not sure the use for the ros::AsyncSpinner or ros::Rate variables.
  6. ros::spin works just fine.
  7. You don't need to callros::shutdown after ros::spin.
  8. create_path is not used and just distracts from the problem.
  9. Only the constructor needs to be public.

Asked by borgcons on 2019-12-22 04:08:15 UTC

Comments