pr2_laser_snapshotter_action.cpp
Go to the documentation of this file.
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_msgs/SetPeriodicCmd.h"
00039 
00040 //Actions
00041 #include "pr2_laser_snapshotter/TiltLaserSnapshotAction.h"
00042 #include "actionlib/server/simple_action_server.h"
00043 
00044 // Messages
00045 #include "sensor_msgs/PointCloud.h"
00046 #include "pr2_msgs/LaserScannerSignal.h"
00047 
00048 #include <boost/thread/mutex.hpp>
00049 
00050 
00051 /***
00052  * This uses the point_cloud_assembler's build_cloud service call to grab all the scans/clouds between two tilt-laser shutters
00053  * params
00054  *  * "~target_frame_id" (string) - This is the frame that the scanned data transformed into.  The
00055  *                                  output clouds are also published in this frame.
00056  */
00057 
00058 namespace pr2_laser_snapshotter
00059 {
00060 
00061 using namespace ros;
00062 using namespace std;
00063 
00064 class PointCloudSrv
00065 {
00066 private:
00067   typedef actionlib::SimpleActionServer<TiltLaserSnapshotAction> Server;
00068   ros::Time laser_time_;
00069   boost::mutex laser_mutex_;
00070   ros::Subscriber sub_;
00071   ros::NodeHandle nh_;
00072   Server cloud_server_;
00073 
00074 public:
00075   PointCloudSrv() : 
00076     cloud_server_(ros::NodeHandle(), "point_cloud_action/single_sweep_cloud", boost::bind(&PointCloudSrv::buildSingleSweepCloud, this, _1), false)
00077   {
00078     sub_ = nh_.subscribe("laser_tilt_controller/laser_scanner_signal", 40, &PointCloudSrv::scannerSignalCallback, this);
00079 
00080     laser_time_ = Time().fromSec(0);
00081     cloud_server_.start();
00082   }
00083 
00084   void buildSingleSweepCloud(const TiltLaserSnapshotGoalConstPtr& goal)
00085   {
00086     // send command to tilt laser scanner
00087     pr2_msgs::SetPeriodicCmd::Request scan_req;
00088     pr2_msgs::SetPeriodicCmd::Response scan_res;
00089     scan_req.command.amplitude  = fabs(goal->angle_end - goal->angle_begin)/2.0;
00090     scan_req.command.offset = (goal->angle_end + goal->angle_begin)/2.0;
00091     scan_req.command.period = goal->duration*2.0;
00092     scan_req.command.profile = "linear";
00093     if (!ros::service::call("laser_tilt_controller/set_periodic_cmd", scan_req, scan_res))
00094     {
00095       std::string error = "PointCloudSrv: error setting laser scanner periodic command";
00096       ROS_ERROR("%s", error.c_str());
00097       cloud_server_.setAborted(TiltLaserSnapshotResult(), error);
00098       return;
00099     }
00100     else
00101       ROS_INFO("PointCloudSrv: commanded tilt laser scanner with period %f, amplitude %f and offset %f",
00102                scan_req.command.period, scan_req.command.amplitude, scan_req.command.offset);
00103 
00104 
00105     // wait for signal from laser to know when scan is finished
00106     Time begin_time = scan_res.start_time;
00107     Duration timeout = Duration().fromSec(2.0);
00108     while (laser_time_ < begin_time){
00109       boost::mutex::scoped_lock laser_lock(laser_mutex_);
00110       if (ros::Time::now() > begin_time + Duration().fromSec(goal->duration) + timeout){
00111         std::string error = "PointCloudSrv: Timeout waiting for laser scan to come in";
00112         ROS_ERROR("%s", error.c_str());
00113         cloud_server_.setAborted(TiltLaserSnapshotResult(), error);
00114         return;
00115       }
00116       laser_lock.unlock();
00117       Duration().fromSec(0.05).sleep();
00118     }
00119     Time end_time = laser_time_;
00120     ROS_INFO("PointCloudSrv: generated point cloud from time %f to %f", begin_time.toSec(), end_time.toSec());
00121 
00122     // get a point cloud from the point cloud assembler
00123     laser_assembler::AssembleScans::Request assembler_req ;
00124     laser_assembler::AssembleScans::Response assembler_res ;
00125     assembler_req.begin = begin_time;
00126     assembler_req.end   = end_time;
00127     if (!ros::service::call("laser_scan_assembler/build_cloud", assembler_req, assembler_res))
00128       ROS_ERROR("PointCloudSrv: error receiving point cloud from point cloud assembler");
00129     else
00130       ROS_INFO("PointCloudSrv: received point cloud of size %d from point cloud assembler", (int)assembler_res.cloud.points.size());
00131 
00132     TiltLaserSnapshotResult res;
00133     res.cloud = assembler_res.cloud;
00134     cloud_server_.setSucceeded(res, "Received a point cloud from the assembler.");
00135     return;
00136   }
00137 
00138 
00139   void scannerSignalCallback(const pr2_msgs::LaserScannerSignalConstPtr& laser_scanner_signal)
00140   {
00141     boost::mutex::scoped_lock laser_lock(laser_mutex_);
00142     // note time when tilt laser is pointing down
00143     if (laser_scanner_signal->signal == 1)
00144     {
00145       laser_time_ = laser_scanner_signal->header.stamp;
00146     }
00147   }
00148 } ;
00149 
00150 }
00151 
00152 
00153 using namespace pr2_laser_snapshotter;
00154 
00155 int main(int argc, char **argv)
00156 {
00157   ros::init(argc, argv, "point_cloud_srv");
00158   PointCloudSrv cloud_srv;
00159 
00160   ros::MultiThreadedSpinner spinner(2);
00161   spinner.spin();
00162 
00163   return 0;
00164 }


pr2_laser_snapshotter
Author(s): Vijay Pradeep
autogenerated on Wed Dec 11 2013 14:17:19