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

Subscribing to topic throw compilation error

asked 2012-06-10 23:52:43 -0500

Erwan R. gravatar image

Hi ROS users !

I'm trying to write a simple controller that takes LaserScan and directly send motor command (in Braitenberg's style), but I'm quite struggling with subscription to node. The subscription method is not recognized when rosmaking and I don't understand what's wrong as I think I doing that the same way as in Writing a Publisher and Subscriber or Publishers and Subscribers.

Any hint would be welcome !

Here is the code :


Class definition

 #ifndef BRAITENBERG_CONTROLLER_H
 #define BRAITENBERG_CONTROLLER_H

 #include <iostream>
 #include <ros/ros.h>

 #include <geometry_msgs/Twist.h>

 #include <tf/transform_listener.h>
 #include <tf/message_filter.h>
 #include <message_filters/subscriber.h>

 #include <laser_geometry/laser_geometry.h>
 #include <sensor_msgs/LaserScan.h>

 namespace braitcontrol {

  class BrController
  {
     private :
        //! The node handle we'll be using
        ros::NodeHandle nh_;
        //! publishing to "/base_controller/command" topic
        ros::Publisher cmd_vel_pub_;
        ros::Subscriber scan_filter_sub_;

         //message_filters::Subscriber<sensor_msgs::LaserScan> scan_filter_sub_;

        tf::MessageFilter<sensor_msgs::LaserScan> * tf_filter_; 
        tf::TransformListener tf_;

        std::string target_frame_;

     public :
        BrController(ros::NodeHandle &nh);

        bool driveBraitenberg();
        sensor_msgs::LaserScan>& laser_ptr);
        void msgCallback(const sensor_msgs::LaserScan & msg);

    };

}

#endif

Class Implementation

#include "braitenberg_controller.h"

using namespace braitcontrol;

BrController::BrController(ros::NodeHandle &nh) : target_frame_("/base_controller/command")
{
   /* Node handle that manage the node and provide publishing and subscribing function */
   nh_ = nh;

   /* Set up the publisher for the cmd_vel topic : we'll publish on this topic to drive the robot */
   cmd_vel_pub_ = nh_.advertise<geometry_msgs::Twist>("/base_controller/command", 1);

   /* Same for subscriber */
   scan_filter_sub_ = nh_.subscribe("scan", 50, msgCallback); // Faulty line !!!
   //tf_filter_ = new tf::MessageFilter<sensor_msgs::LaserScan>(scan_filter_sub_, tf_, target_frame_, 10);    
}

 void BrController::msgCallback(const sensor_msgs::LaserScan & msg)
 {
    std::cout << "Callback" << std::endl;
 }

 bool BrController::driveBraitenberg()
 {
    // Just driving robot according a constant rotation command
    //we are sending commands of type "twist" to drive the robot
    geometry_msgs::Twist base_cmd;


float cmd = 50.0;

    while(nh_.ok())
    {       
     base_cmd.angular.z = cmd;
         //publish the assembled command
         cmd_vel_pub_.publish(base_cmd);
    }

  return true;
}

int main(int argc, char** argv)
{
  //init the ROS node
  ros::init(argc, argv, "braitenberg_controller");
  ros::NodeHandle nh;

  BrController bControl(nh);
  bControl.driveBraitenberg();

  return 0;
}

And here is the error :

  [100%] Building CXX object CMakeFiles/pr2_braitenberg_controller.dir/src/braitenberg_controller.o
/home/renaudo/ros_workspace/pr2_braitenberg_controller/src/braitenberg_controller.cpp:
    In constructor ‘braitcontrol::BrController::BrController(ros::NodeHandle&)’:
/home/renaudo/ros_workspace/pr2_braitenberg_controller/src/braitenberg_controller.cpp:13: error:
    no matching function for call to ‘ros::NodeHandle::subscribe(const char [5], int, <unresolved overloaded function type>)’
/opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include/ros/node_handle.h:785: note:
    candidates are: ros::Subscriber   ros::NodeHandle::subscribe(ros::SubscribeOptions&)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
6

answered 2012-06-11 00:13:27 -0500

karthik gravatar image

updated 2012-06-11 01:04:06 -0500

Hi, Change the following

scan_filter_sub_ = nh_.subscribe("scan", 50, msgCallback);

to

scan_filter_sub_ = nh_.subscribe("scan", 50, &BrController::msgCallback, this);

And you have to remove ')' in the .h file at line num 38.

Hope it resolves the issue.

Thanks, Karthik

edit flag offensive delete link more

Comments

1

Thanks for answering ! I tried that but error is the same except that the third argument is not "unresolved overloaded function type" but "void (braitcontrol::BrController::)(const sensor_msgs::LaserScan&)"*. It is still asking for SubscriberOptions but ...

Erwan R. gravatar image Erwan R.  ( 2012-06-11 00:25:03 -0500 )edit

... I saw examples without using this structure (and that are supposed to work even if I didn't run them). At least, this (giving the right pointer) is correcting another issue.

Erwan R. gravatar image Erwan R.  ( 2012-06-11 00:25:34 -0500 )edit

I just updated my answer with "this". Try n let me know

karthik gravatar image karthik  ( 2012-06-11 00:55:42 -0500 )edit

It's now compiling but it seems that it's never receiving messages (even when remaped on /base_scan or /base_scan_throttled ). Laser are enabled with launching gmapping and checked with rViz. According to th Terminal output, only driveBraitenberg is executed and never the callback.

Erwan R. gravatar image Erwan R.  ( 2012-06-11 03:06:19 -0500 )edit

Could you post this issue as a new question so that people will respond to it.

karthik gravatar image karthik  ( 2012-06-11 05:08:13 -0500 )edit

Hi Erwan. i'm having exactly your last problem: my callback is never executed. how did you solved the issue?

rouch gravatar image rouch  ( 2014-04-16 05:08:23 -0500 )edit

Hello Rouch. I don't really remember what was the exact problem and the solution. From reading the code again, I guess it may be the lack of "ros::SpinOnce()" in the driveBraitenberg function. If that doesn't solve your problem, open a new question with details, I'll give it a try.

Erwan R. gravatar image Erwan R.  ( 2014-04-16 11:58:04 -0500 )edit

No, was exactly that the problem, i wasn't spinning the callback queue. Shame on me :) thank you for the answer!

rouch gravatar image rouch  ( 2014-04-20 02:55:39 -0500 )edit

Question Tools

Stats

Asked: 2012-06-10 23:52:43 -0500

Seen: 3,564 times

Last updated: Jun 11 '12