$search
00001 /********************************************************************* * Software License Agreement (BSD License) 00002 * 00003 * Copyright (c) 2008, Willow Garage, Inc. 00004 * All rights reserved. 00005 * 00006 * Redistribution and use in source and binary forms, with or without 00007 * modification, are permitted provided that the following conditions 00008 * are met: 00009 * 00010 * * Redistributions of source code must retain the above copyright 00011 * notice, this list of conditions and the following disclaimer. 00012 * * Redistributions in binary form must reproduce the above 00013 * copyright notice, this list of conditions and the following 00014 * disclaimer in the documentation and/or other materials provided 00015 * with the distribution. 00016 * * Neither the name of the Willow Garage nor the names of its 00017 * contributors may be used to endorse or promote products derived 00018 * from this software without specific prior written permission. 00019 * 00020 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 * POSSIBILITY OF SUCH DAMAGE. 00032 *********************************************************************/ 00033 00034 #include <ros/ros.h> 00035 00036 // Services 00037 #include "laser_assembler/AssembleScans.h" 00038 #include "pr2_arm_navigation_perception/BuildCloudAngle.h" 00039 #include "pr2_msgs/SetPeriodicCmd.h" 00040 00041 // Messages 00042 #include "sensor_msgs/PointCloud.h" 00043 #include "pr2_msgs/LaserScannerSignal.h" 00044 00045 #include <boost/thread/mutex.hpp> 00046 00047 00048 /*** 00049 * This uses the point_cloud_assembler's build_cloud service call to grab all the scans/clouds between two tilt-laser shutters 00050 * params 00051 * * "~target_frame_id" (string) - This is the frame that the scanned data transformed into. The 00052 * output clouds are also published in this frame. 00053 */ 00054 00055 namespace pr2_laser_snapshotter 00056 { 00057 00058 using namespace ros; 00059 using namespace std; 00060 00061 class PointCloudSrv 00062 { 00063 private: 00064 ros::Time laser_time_; 00065 boost::mutex laser_mutex_; 00066 ros::ServiceServer cloud_server_; 00067 ros::Subscriber sub_; 00068 ros::NodeHandle nh_; 00069 00070 public: 00071 PointCloudSrv() 00072 { 00073 cloud_server_ = nh_.advertiseService("point_cloud_srv/single_sweep_cloud", &PointCloudSrv::buildSingleSweepCloud, this); 00074 sub_ = nh_.subscribe("laser_tilt_controller/laser_scanner_signal", 40, &PointCloudSrv::scannerSignalCallback, this); 00075 00076 laser_time_ = Time().fromSec(0); 00077 } 00078 00079 bool buildSingleSweepCloud(pr2_arm_navigation_perception::BuildCloudAngle::Request &req, 00080 pr2_arm_navigation_perception::BuildCloudAngle::Response &res) 00081 { 00082 // send command to tilt laser scanner 00083 pr2_msgs::SetPeriodicCmd::Request scan_req; 00084 pr2_msgs::SetPeriodicCmd::Response scan_res; 00085 scan_req.command.amplitude = fabs(req.angle_end - req.angle_begin)/2.0; 00086 scan_req.command.offset = (req.angle_end + req.angle_begin)/2.0; 00087 scan_req.command.period = req.duration*2.0; 00088 scan_req.command.profile = "linear"; 00089 if (!ros::service::call("laser_tilt_controller/set_periodic_cmd", scan_req, scan_res)) 00090 ROS_ERROR("PointCloudSrv: error setting laser scanner periodic command"); 00091 else 00092 ROS_INFO("PointCloudSrv: commanded tilt laser scanner with period %f, amplitude %f and offset %f", 00093 scan_req.command.period, scan_req.command.amplitude, scan_req.command.offset); 00094 00095 00096 // wait for signal from laser to know when scan is finished 00097 Time begin_time = scan_res.start_time; 00098 Duration timeout = Duration().fromSec(2.0); 00099 while (laser_time_ < begin_time){ 00100 boost::mutex::scoped_lock laser_lock(laser_mutex_); 00101 if (ros::Time::now() > begin_time + Duration().fromSec(req.duration) + timeout){ 00102 ROS_ERROR("PointCloudSrv: Timeout waiting for laser scan to come in"); 00103 return false; 00104 } 00105 laser_lock.unlock(); 00106 Duration().fromSec(0.05).sleep(); 00107 } 00108 Time end_time = laser_time_; 00109 ROS_INFO("PointCloudSrv: generated point cloud from time %f to %f", begin_time.toSec(), end_time.toSec()); 00110 00111 // get a point cloud from the point cloud assembler 00112 laser_assembler::AssembleScans::Request assembler_req ; 00113 laser_assembler::AssembleScans::Response assembler_res ; 00114 assembler_req.begin = begin_time; 00115 assembler_req.end = end_time; 00116 if (!ros::service::call("laser_scan_assembler/build_cloud", assembler_req, assembler_res)) 00117 ROS_ERROR("PointCloudSrv: error receiving point cloud from point cloud assembler"); 00118 else 00119 ROS_INFO("PointCloudSrv: received point cloud of size %i from point cloud assembler", assembler_res.cloud.points.size()); 00120 00121 res.cloud = assembler_res.cloud; 00122 return true; 00123 } 00124 00125 00126 void scannerSignalCallback(const pr2_msgs::LaserScannerSignalConstPtr& laser_scanner_signal) 00127 { 00128 boost::mutex::scoped_lock laser_lock(laser_mutex_); 00129 // note time when tilt laser is pointing down 00130 if (laser_scanner_signal->signal == 1) 00131 { 00132 laser_time_ = laser_scanner_signal->header.stamp; 00133 } 00134 } 00135 } ; 00136 00137 } 00138 00139 00140 using namespace pr2_laser_snapshotter; 00141 00142 int main(int argc, char **argv) 00143 { 00144 ros::init(argc, argv, "point_cloud_srv"); 00145 PointCloudSrv cloud_srv; 00146 00147 ros::MultiThreadedSpinner spinner(2); 00148 spinner.spin(); 00149 00150 return 0; 00151 }