$search
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 // Services 00038 #include "laser_assembler/AssembleScans.h" 00039 00040 // Messages 00041 #include "sensor_msgs/PointCloud.h" 00042 #include "pr2_msgs/LaserScannerSignal.h" 00043 00044 /*** 00045 * This uses the point_cloud_assembler's build_cloud service call to grab all the scans/clouds between two tilt-laser shutters 00046 * params 00047 * * "~target_frame_id" (string) - This is the frame that the scanned data transformed into. The 00048 * output clouds are also published in this frame. 00049 * * "~num_skips" (int) - If set to N>0, then the snapshotter will skip N signals before 00050 * requesting a new snapshot. This will make the snapshots be N times 00051 * larger. Default 0 - no skipping. 00052 */ 00053 00054 namespace pr2_laser_snapshotter 00055 { 00056 00057 class PR2LaserSnapshotter 00058 { 00059 00060 public: 00061 ros::NodeHandle n_; 00062 ros::NodeHandle private_ns_; 00063 ros::Publisher pub_; 00064 ros::Subscriber sub_; 00065 00066 pr2_msgs::LaserScannerSignal prev_signal_; 00067 00068 bool first_time_; 00069 00070 int num_skips_; 00071 int num_skips_left_; 00072 00073 std::string fixed_frame_; 00074 00075 PR2LaserSnapshotter() : private_ns_("~") 00076 { 00077 prev_signal_.header.stamp.fromNSec(0); 00078 00079 pub_ = n_.advertise<sensor_msgs::PointCloud> ("full_cloud", 1); 00080 sub_ = n_.subscribe("laser_scanner_signal", 40, &PR2LaserSnapshotter::scannerSignalCallback, this); 00081 00082 private_ns_.param("num_skips", num_skips_, 0); 00083 num_skips_left_=num_skips_; 00084 00085 first_time_ = true; 00086 } 00087 00088 ~PR2LaserSnapshotter() 00089 { 00090 00091 } 00092 00093 void scannerSignalCallback(const pr2_msgs::LaserScannerSignalConstPtr& cur_signal) 00094 { 00095 if (cur_signal->signal == 128 || cur_signal->signal == 129) // These codes imply that this is the first signal during a given profile type 00096 first_time_ = true; 00097 00098 00099 if (first_time_) 00100 { 00101 prev_signal_ = *cur_signal; 00102 first_time_ = false; 00103 } 00104 else 00105 { 00106 if(num_skips_>0) 00107 { 00108 if(num_skips_left_>0) 00109 { 00110 num_skips_left_ -= 1; 00111 return; 00112 } 00113 else 00114 { 00115 num_skips_left_=num_skips_; 00116 } 00117 } 00118 00119 laser_assembler::AssembleScans::Request req; 00120 laser_assembler::AssembleScans::Response resp; 00121 00122 req.begin = prev_signal_.header.stamp; 00123 req.end = cur_signal->header.stamp; 00124 00125 if (!ros::service::call("assemble_scans", req, resp)) 00126 ROS_ERROR("Failed to call service on point cloud assembler or laser scan assembler."); 00127 00128 pub_.publish(resp.cloud); 00129 ROS_DEBUG("Snapshotter::Published Cloud size=%u", resp.cloud.get_points_size()); 00130 00131 prev_signal_ = *cur_signal; 00132 } 00133 } 00134 } ; 00135 00136 } 00137 00138 using namespace pr2_laser_snapshotter; 00139 00140 int main(int argc, char **argv) 00141 { 00142 ros::init(argc, argv, "pr2_laser_snapshotter"); 00143 PR2LaserSnapshotter snapshotter ; 00144 ros::spin(); 00145 return 0; 00146 }