dense_laser_snapshotter.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include "ros/ros.h"
00036 
00037 #include <dense_laser_assembler/dense_laser_assembler.h>
00038 
00039 // Messages
00040 #include "sensor_msgs/LaserScan.h"
00041 #include "calibration_msgs/DenseLaserSnapshot.h"
00042 #include "pr2_msgs/LaserScannerSignal.h"
00043 
00044 using namespace dense_laser_assembler ;
00045 
00049 class DenseLaserSnapshotter
00050 {
00051 
00052 public:
00053 
00054   DenseLaserSnapshotter()
00055   {
00056     assembler_.setCacheSize(40*20);
00057     prev_signal_.header.stamp = ros::Time(0, 0);
00058     signal_sub_ = n_.subscribe("laser_tilt_controller/laser_scanner_signal", 2, &DenseLaserSnapshotter::scannerSignalCallback, this);
00059     scan_sub_ = n_.subscribe("scan", 1, &DenseLaserSnapshotter::scanCallback, this);
00060     snapshot_pub_ = n_.advertise<calibration_msgs::DenseLaserSnapshot> ("dense_laser_snapshot", 1);
00061     first_time_ = true;
00062   }
00063 
00064   ~DenseLaserSnapshotter()
00065   {
00066 
00067   }
00068 
00069   void scanCallback(const sensor_msgs::LaserScanConstPtr& scan)
00070   {
00071     assembler_.add(scan);
00072   }
00073 
00074   void scannerSignalCallback(const pr2_msgs::LaserScannerSignalConstPtr& cur_signal)
00075   {
00076     ROS_DEBUG("Got Scanner Signal") ;
00077 
00078     if (first_time_)
00079     {
00080       prev_signal_ = *cur_signal ;
00081       first_time_ = false ;
00082     }
00083     else
00084     {
00085       if (cur_signal->signal == 1)
00086       {
00087         ROS_DEBUG("About to make request");
00088 
00089         ros::Time start = prev_signal_.header.stamp;
00090         ros::Time end = cur_signal->header.stamp;
00091 
00092         calibration_msgs::DenseLaserSnapshot snapshot;
00093 
00094         assembler_.assembleSnapshot(start, end, snapshot);
00095 
00096         ROS_DEBUG("header.stamp: %f", snapshot.header.stamp.toSec());
00097         ROS_DEBUG("header.frame_id: %s", snapshot.header.frame_id.c_str());
00098         ROS_DEBUG("ranges.size()=%u", snapshot.ranges.size());
00099         ROS_DEBUG("intensities.size()=%u", snapshot.intensities.size());
00100         ROS_DEBUG("scan_start.size()=%u", snapshot.scan_start.size());
00101         snapshot_pub_.publish(snapshot);
00102       }
00103       else
00104         ROS_DEBUG("Not making request");
00105       prev_signal_ = *cur_signal;
00106     }
00107   }
00108 
00109 private:
00110   ros::NodeHandle n_;
00111   ros::Publisher snapshot_pub_;
00112   ros::Subscriber signal_sub_;
00113   ros::Subscriber scan_sub_;
00114   DenseLaserAssembler assembler_;
00115   pr2_msgs::LaserScannerSignal prev_signal_;
00116 
00117   bool first_time_ ;
00118 };
00119 
00120 int main(int argc, char **argv)
00121 {
00122   ros::init(argc, argv, "dense_laser_snapshotter") ;
00123   DenseLaserSnapshotter snapshotter ;
00124   ros::spin() ;
00125 
00126   return 0;
00127 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


pr2_dense_laser_snapshotter
Author(s): Vijay Pradeep
autogenerated on Thu Aug 15 2013 13:01:35