36 #include <calibration_msgs/IntervalStamped.h> 44 const calibration_msgs::DenseLaserSnapshotConstPtr& snapshot,
45 const calibration_msgs::CalibrationPatternConstPtr& features)
47 calibration_msgs::IntervalStamped out;
55 ROS_WARN(
"Failed trying to compute interval. Not going to publish");
59 out.header.stamp = snapshot->header.stamp;
63 int main(
int argc,
char** argv)
65 ros::init(argc, argv,
"laser_interval_calc");
74 calibration_msgs::CalibrationPattern> sync(snapshot_sub, features_sub, 2);
75 sync.registerCallback(boost::bind(&
syncCallback, &pub, _1, _2));
static bool computeInterval(const calibration_msgs::DenseLaserSnapshot &snapshot, const calibration_msgs::CalibrationPattern &features, calibration_msgs::Interval &result)
void syncCallback(ros::Publisher *pub, const calibration_msgs::DenseLaserSnapshotConstPtr &snapshot, const calibration_msgs::CalibrationPatternConstPtr &features)
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char **argv)