laser_interval_calc_node.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <ros/ros.h>
36 #include <calibration_msgs/IntervalStamped.h>
40 
41 using namespace laser_cb_detector;
42 
44  const calibration_msgs::DenseLaserSnapshotConstPtr& snapshot,
45  const calibration_msgs::CalibrationPatternConstPtr& features)
46 {
47  calibration_msgs::IntervalStamped out;
48 
49  bool success;
50 
51  success = LaserIntervalCalc::computeInterval(*snapshot, *features, out.interval);
52 
53  if (!success)
54  {
55  ROS_WARN("Failed trying to compute interval. Not going to publish");
56  return;
57  }
58 
59  out.header.stamp = snapshot->header.stamp;
60  pub->publish(out);
61 }
62 
63 int main(int argc, char** argv)
64 {
65  ros::init(argc, argv, "laser_interval_calc");
66 
67  ros::NodeHandle nh;
68 
69  ros::Publisher pub = nh.advertise<calibration_msgs::IntervalStamped>("laser_interval", 1);
70 
73  message_filters::TimeSynchronizer<calibration_msgs::DenseLaserSnapshot,
74  calibration_msgs::CalibrationPattern> sync(snapshot_sub, features_sub, 2);
75  sync.registerCallback(boost::bind(&syncCallback, &pub, _1, _2));
76 
77  ros::spin();
78 
79  return 0;
80 }
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)
#define ROS_WARN(...)
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)


laser_cb_detector
Author(s): Vijay Pradeep
autogenerated on Thu Jun 6 2019 19:17:28