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

How to use ApproximateTime policy in class in cpp?

asked 2020-05-11 12:37:22 -0500

Burhan gravatar image

updated 2020-05-13 01:33:33 -0500

Hi all. I am new in ROS and especially roscpp. So, my purpose is to get range values from 5 infrared sensors and print them in callback. After searching in google, I found that I have to use message_filters/ApproximateTime policy. I tried my best to apply. After compiling I have got many errors. While I could correct some of them, I couldn't handle others. Please, can you help me in order to find the source of error? Thank you very much :)

Edit: So, basically I made some corrections on my code and it compiles without any error. But, the problem is the allback function doesn't be called. What can be the problem? Thank you :)

My code (Didn't append main function):

#include <ros/ros.h>
#include <nav_msgs/Odometry.h>
#include <sensor_msgs/Range.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <math.h>

using namespace nav_msgs;
using namespace sensor_msgs;
using namespace message_filters;

/*

sensors 0-4  are ultrasonic sensors
sensors 5-10 are infrared sensors

*/


class AvoidObstacle
{
private:
    ros::NodeHandle nh;

public:
    void ReadDistanceSensors(const RangeConstPtr&,const RangeConstPtr&,const RangeConstPtr&,const RangeConstPtr&,const RangeConstPtr&);
    AvoidObstacle();
};

AvoidObstacle::AvoidObstacle()
{
    message_filters::Subscriber<Range> sonar0_sub(nh, "/robot0/sonar_0", 1);
    message_filters::Subscriber<Range> sonar1_sub(nh, "/robot0/sonar_1", 1);
    message_filters::Subscriber<Range> sonar2_sub(nh, "/robot0/sonar_2", 1);
    message_filters::Subscriber<Range> sonar3_sub(nh, "/robot0/sonar_3", 1);
typedef sync_policies::ApproximateTime<Range, Range, Range, Range, Range> MySyncPolicy;
    Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), sonar0_sub, sonar1_sub, sonar2_sub, sonar3_sub, sonar4_sub);
    sync.registerCallback(boost::bind(&AvoidObstacle::ReadDistanceSensors, this, _1, _2, _3, _4, _5));
    ROS_INFO("Hello");
}

void AvoidObstacle::ReadDistanceSensors(const RangeConstPtr& sn0,const RangeConstPtr& sn1,const RangeConstPtr& sn2,const RangeConstPtr& sn3,const RangeConstPtr& sn4)
{
    ROS_INFO("range: %lf", sn0->range);
}
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-11-13 06:24:53 -0500

alcantara gravatar image

I don't know if this is still a problem. But the way the Synchronizer using a ApproximateTime policy works is trying to find a set of messages in the subscriber queue that satisfy a time constraint. Your callback function is going to be called only when you have this set of aligned messages .You can see more details in http://wiki.ros.org/message_filters/A....

In your particular case, you are trying to find a set of 4 messages that are aligned in time, however the queue size in each subscriber is set to 1. This means that you have to receive 4 messages already synchronized, what has little probability to occur and also kind of breaks the purpose of the Synchronizer existence in the first place. So I would recommend you to increase the queue size of each Subscriber so the Synchronizer has more room to select the best set and also drop the messages that are not relevant anymore.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-05-11 12:37:22 -0500

Seen: 536 times

Last updated: May 13 '20