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

[Solved] C++: ApproximateTime with more than two topics?

asked 2017-03-06 08:36:09 -0500

BlenderEi gravatar image

updated 2017-03-16 08:04:09 -0500

Hi @all,

short version:

Could you please provide me with a full version for synchronizing up to eight image topics with ROS?

long version:

I am currently trying to get my Synchronizer to work. Thanks to this forum I was able to get a Synchronizer to work with two topics (for interested users, see: http://wiki.ros.org/message_filters?d... ).

Now, all I have found so far deals with two topics. In my case, there are more than two topics (namely, four, six or eight image topics). I need to synchronize them too. And using ApproximateTime for that looks like a good option to me. However, I am getting errors doing so.

Essential code for two topics (Working):

#include <sensor_msgs/Image.h>

#include <image_transport/subscriber_filter.h>

#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>

class My_Synchronizer {

private:
 ros::NodeHandle nh_;
 image_transport::ImageTransport it_;

 typedef image_transport::SubscriberFilter ImageSubscriber;
 typedef ros::Publisher                    ImagePublisher;

 ImageSubscriber img1_sub_;
 ImageSubscriber img2_sub_;

 ImagePublisher img1_pub_;
 ImagePublisher img2_pub_;

 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> ImageSyncPolicy_1; //two topics

 message_filters::Synchronizer< ImageSyncPolicy_1 > sync_1;

//Constructor for two topics:
My_Synchronizer(
std::string t1,
std::string t2
) :
it_(nh_),
img1_sub_( it_, t1, 100),
img2_sub_( it_, t2, 100),
sync_1( ImageSyncPolicy_1( 10 ), img1_sub_, img2_sub_)
{


  img1_pub_ = nh_.advertise<sensor_msgs::Image>("/synchronized/" + t1, 1000);
  img2_pub_ = nh_.advertise<sensor_msgs::Image>("/synchronized/" + t2, 1000);


  std::cout << "Image Synchronizer on two topics started" << std::endl;
  sync_1.registerCallback( boost::bind( &My_Synchronizer::Sync1_Callback, this, _1, _2) );
};

void Sync1_Callback(
/*
  Callback with two synchronized topics:
*/
  const sensor_msgs::ImageConstPtr& image1,
  const sensor_msgs::ImageConstPtr& image2
 );
};
//Implementation of Sync1_Callback in separate file - not important for this question

Changes in Code for eight topics (Not Working!):

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> ImageSyncPolicy_4; //eight topics

message_filters::Synchronizer< ImageSyncPolicy_4 > sync_4; //Does not work, but [...] sync_4(); works - still problems below

 //Constructor for eight topics:
 My_Synchronizer(
 std::string t1,
 std::string t2,
 [...]
 ) :
 it_(nh_),
 img1_sub_( it_, t1, 100),
 img2_sub_( it_, t2, 100),
 [...]
 sync_4( ImageSyncPolicy_1( 10 ), img1_sub_, img2_sub_, img3_sub_, img4_sub_, img5_sub_, img6_sub_, img7_sub_, img8_sub_)
 {

  img1_pub_ = nh_.advertise<sensor_msgs::Image>("/synchronized/" + t1, 1000);
  img2_pub_ = nh_.advertise<sensor_msgs::Image>("/synchronized/" + t2, 1000);
  [...]

  std::cout << "Image Synchronizer on eight topics started" << std::endl;
  sync_4.registerCallback( boost::bind( &My_Synchronizer::Sync4_Callback, this, _1, _2, _3, _4, _5, _6, _7, _8) );
};

 void Sync4_Callback(
 /*
   Callback with eight synchronized topics:
 */
  const sensor_msgs::ImageConstPtr& image1,
  const sensor_msgs::ImageConstPtr& image2,
  const sensor_msgs::ImageConstPtr& image3,
  const sensor_msgs::ImageConstPtr& image4,
  const sensor_msgs::ImageConstPtr& image5,
  const sensor_msgs::ImageConstPtr& image6,
  const sensor_msgs::ImageConstPtr& image7,
  const sensor_msgs::ImageConstPtr& image8
 );

The above code throws many boost related errors, about missing arguments or wrong function calls. I cannot really find out where the necessary change is to be made. Trying to use a SyncPolicy for four topics already throws this error for example:

error: no matching function for call to ‘message_filters::sync_policies::ApproximateTime<sensor_msgs::Image_<std::allocator<void> >, sensor_msgs::Image_<std::allocator<void> >, sensor_msgs::Image_<std::allocator<void> >, sensor_msgs::Image_<std::allocator<void> > >::ApproximateTime()’

Could you please tell me ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
3

answered 2017-03-16 08:03:00 -0500

BlenderEi gravatar image

Ok guys, I am going to answer my own question here. Just for the other users, if they face the same problem.

Here is a full example handling up to four separate image topics.

#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <sensor_msgs/Image.h>

using namespace sensor_msgs;
using namespace message_filters;

ros::Publisher image1_pub;
ros::Publisher image2_pub;
ros::Publisher image3_pub;
ros::Publisher image4_pub;


void callback(const ImageConstPtr& image1, const ImageConstPtr& image2, const ImageConstPtr& image3, const ImageConstPtr& image4)
{
  // Solve all of perception here...
  ROS_INFO("Sync_Callback");

  image1_pub.publish(image1);
  image2_pub.publish(image2);
  image3_pub.publish(image3);
  image4_pub.publish(image4);

}

int main(int argc, char** argv)
{
  ros::init(argc, argv, "vision_node");

  std::string zed1_img_topic = "/zed_rear_right/left/image_raw_color";
  std::string zed2_img_topic = "/zed_rear_right/right/image_raw_color";
  std::string zed3_img_topic = "/zed_rear_right/left/image_raw_color";
  std::string zed4_img_topic = "/zed_rear_right/right/image_raw_color";


  ros::NodeHandle nh;
  message_filters::Subscriber<Image> image1_sub(nh, zed1_img_topic, 100);
  message_filters::Subscriber<Image> image2_sub(nh, zed2_img_topic, 100);
  message_filters::Subscriber<Image> image3_sub(nh, zed3_img_topic, 100);
  message_filters::Subscriber<Image> image4_sub(nh, zed4_img_topic, 100);

  image1_pub = nh.advertise<sensor_msgs::Image>("/synchronized" + zed1_img_topic, 1000);
  image2_pub = nh.advertise<sensor_msgs::Image>("/synchronized" + zed2_img_topic, 1000);
  image3_pub = nh.advertise<sensor_msgs::Image>("/synchronized" + zed3_img_topic, 1000);
  image4_pub = nh.advertise<sensor_msgs::Image>("/synchronized" + zed4_img_topic, 1000);



  typedef sync_policies::ApproximateTime<Image, Image, Image, Image> MySyncPolicy;
  // ApproximateTime takes a queue size as its constructor argument, hence MySyncPolicy(10)
  Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), image1_sub, image2_sub, image3_sub, image4_sub);
  sync.registerCallback(boost::bind(&callback, _1, _2, _3, _4));


  ros::spin();

  return 0;
}

Note: Above code is based on the given example (see http://wiki.ros.org/message_filters?d... ).

I was not really able to solve the original errors, since it seems that it is not really ROS related, but rather how my classes are structured. I decided to not use the class from now on further but use global variables instead. However, I will mark this thread as resolved, since the task can be accomplished with this code.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2017-03-06 08:36:09 -0500

Seen: 2,822 times

Last updated: Mar 16 '17