Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 #include <ros/ros.h>
00036 #include <calibration_msgs/IntervalStamped.h>
00037 #include <laser_cb_detector/laser_interval_calc.h>
00038 #include <message_filters/subscriber.h>
00039 #include <message_filters/time_synchronizer.h>
00040 
00041 using namespace laser_cb_detector;
00042 
00043 void syncCallback(ros::Publisher* pub,
00044                   const calibration_msgs::DenseLaserSnapshotConstPtr& snapshot,
00045                   const calibration_msgs::CalibrationPatternConstPtr& features)
00046 {
00047   calibration_msgs::IntervalStamped out;
00048 
00049   bool success;
00050 
00051   success = LaserIntervalCalc::computeInterval(*snapshot, *features, out.interval);
00052 
00053   if (!success)
00054   {
00055     ROS_WARN("Failed trying to compute interval. Not going to publish");
00056     return;
00057   }
00058 
00059   out.header.stamp = snapshot->header.stamp;
00060   pub->publish(out);
00061 }
00062 
00063 int main(int argc, char** argv)
00064 {
00065   ros::init(argc, argv, "laser_interval_calc");
00066 
00067   ros::NodeHandle nh;
00068 
00069   ros::Publisher pub = nh.advertise<calibration_msgs::IntervalStamped>("laser_interval", 1);
00070 
00071   message_filters::Subscriber<calibration_msgs::DenseLaserSnapshot> snapshot_sub(nh, "snapshot", 1);
00072   message_filters::Subscriber<calibration_msgs::CalibrationPattern> features_sub(nh, "features", 1);
00073   message_filters::TimeSynchronizer<calibration_msgs::DenseLaserSnapshot,
00074                                     calibration_msgs::CalibrationPattern> sync(snapshot_sub, features_sub, 2);
00075   sync.registerCallback(boost::bind(&syncCallback, &pub, _1, _2));
00076 
00077   ros::spin();
00078 
00079   return 0;
00080 }