Problem in synchronizing topics via ApproximateTime synchronizer

asked 2020-02-22 04:39:40 -0500

rayane gravatar image

updated 2020-02-22 08:40:59 -0500

Hi, I want to synchronize the saved images using the node image_saver with the velocity of the camera of the bebop. I want to publish both synchronized data (provided from /bebop/imageraw and /bebop/cmd_vel topics) in another two different topics and then use the node mage_saver to subscribe to the synchronized imageraw topic to save them. I got inspired from this code.

My implementation is like below:

#include <boost/bind.hpp>
#include <ros/console.h>
#include <ros/param.h>
#include <ros/ros.h>

 #include <image_transport/image_transport.h>

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

 #include <sensor_msgs/CameraInfo.h>
 #include <sensor_msgs/Image.h>

#include <tf/transform_listener.h>
#include <geometry_msgs/TwistStamped.h>
#include <std_msgs/Float32.h>
#include <cmath>
#include <cstdlib>
#include <std_msgs/String.h>
#include <nav_msgs/Odometry.h>


  typedef message_filters::sync_policies::ApproximateTime<
  sensor_msgs::Image, geometry_msgs::TwistStamped >


 void imageCallback(ros::Publisher& pub_vel_,
       ros::Publisher& pub_cam_,
       const sensor_msgs::Image& msg_img,
       const geometry_msgs::TwistStamped& msg_vel
               )
    {
       sensor_msgs::Image new_img_;
      geometry_msgs::TwistStamped new_vel_;

       // Fix timestamps.
      // FIXME: a warning should be issued if the differences between
     // timestamps are too important.
    new_img_= msg_img;
   new_vel_.header.stamp = msg_img.header.stamp;
   new_vel_.twist = msg_vel.twist;

    pub_cam_.publish(new_img_);
  pub_vel_.publish(new_vel_);
  }


   /// \brief Main entry point.
   int main(int argc, char **argv)
    {
    // ROS initialization.
    ros::init(argc, argv, "fake_camera_synchronizer");


    // Node initialization.
     ros::NodeHandle nh;

     // Publishers creation.
    ros::Publisher pub_cam_ =
     nh.advertise<sensor_msgs::Image>("/bebop/imageraw_synchronised", 1); 
     ros::Publisher pub_vel_ =
     nh.advertise<geometry_msgs::TwistStamped>("/bebop/velocity_synchronised", 1);

      // Subscribers creation.
    message_filters::Subscriber<sensor_msgs::Image>
    sub_cam_(nh,"msg_img", 1);
   message_filters::Subscriber<geometry_msgs::TwistStamped>
    sub_vel_(nh, "msg_vel", 1);

     // Message filter creation.
  message_filters::Synchronizer<policy_t> sync
(policy_t(10), sub_cam_, sub_vel_);

  sync.registerCallback
   (boost::bind(imageCallback,
     boost::ref(pub_cam_), boost::ref(pub_vel_),
     _1, _2));

 ros::spin();

}

and this is the error I get :

[ 98%] Built target auto_tracker
[ 98%] Built target visp_auto_tracker
In file included from /usr/include/boost/bind.hpp:22:0,
                 from /home/rayane/catkin_ws/src/bebop_pkg/src/data_synchronizer_2.cpp:1:
/usr/include/boost/bind/bind.hpp: In instantiation of ‘void boost::_bi::list4<A1, A2, A3, A4>::operator()(boost::_bi::type<void>, F&, A&, int) [with F = void (*)(ros::Publisher&, ros::Publisher&, const sensor_msgs::Image_<std::allocator<void> >&, const geometry_msgs::TwistStamped_<std::allocator<void> >&); A = boost::_bi::list9<const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, const boost::shared_ptr<const geometry_msgs::TwistStamped_<std::allocator<void> > >&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&>; A1 = boost::reference_wrapper<ros::Publisher>; A2 = boost::reference_wrapper<ros::Publisher>; A3 = boost::arg<1>; A4 = boost::arg<2>]’:
/usr/include/boost/bind/bind_template.hpp:305:59:   required from ‘boost::_bi::bind_t<R, F, L>::result_type boost::_bi::bind_t<R, F, L>::operator()(const A1&, const A2&, const A3&, const A4&, const A5&, const A6&, const A7&, const A8&, const A9&) [with A1 = boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >; A2 = boost::shared_ptr<const geometry_msgs::TwistStamped_<std::allocator<void> > >; A3 = boost::shared_ptr<const message_filters::NullType>; A4 = boost::shared_ptr<const message_filters::NullType>; A5 = boost::shared_ptr<const message_filters::NullType>; A6 = boost::shared_ptr<const ...
(more)
edit retag flag offensive close merge delete