grid_construction_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  */
00030 
00031 
00040 #include <occupancy_grid_utils/ray_tracer.h>
00041 #include <laser_geometry/laser_geometry.h>
00042 #include <tf/transform_listener.h>
00043 #include <ros/ros.h>
00044 #include <boost/circular_buffer.hpp>
00045 #include <boost/optional.hpp>
00046 #include <boost/foreach.hpp>
00047 
00048 namespace grid_construction_node
00049 {
00050 
00051 namespace gm=geometry_msgs;
00052 namespace sm=sensor_msgs;
00053 namespace nm=nav_msgs;
00054 namespace gu=occupancy_grid_utils;
00055 
00056 using std::vector;
00057 using std::string;
00058 
00059 typedef boost::mutex::scoped_lock Lock;
00060 typedef boost::shared_ptr<gu::LocalizedCloud> CloudPtr;
00061 typedef boost::shared_ptr<gu::LocalizedCloud const> CloudConstPtr;
00062 typedef boost::circular_buffer<CloudConstPtr> CloudBuffer;
00063 
00064 class GridConstructionNode
00065 {
00066 public:
00067   GridConstructionNode ();
00068 
00069 private:
00070 
00071   void scanCallback (const sm::LaserScan& scan);
00072   void buildGrid (const ros::WallTimerEvent& e);
00073 
00074   /****************************************
00075    * Params
00076    ****************************************/
00077 
00078   const unsigned history_length_;
00079   const double resolution_;
00080   const string fixed_frame_;
00081   const string sensor_frame_;
00082   const double grid_construction_interval_;
00083   const double local_grid_size_;
00084 
00085   /****************************************
00086    * Associated objects
00087    ****************************************/
00088 
00089   ros::NodeHandle nh_;
00090   tf::TransformListener tf_;
00091   ros::Subscriber scan_sub_;
00092   ros::Publisher grid_pub_;
00093   ros::WallTimer build_grid_timer_;
00094   boost::mutex mutex_;
00095   
00096   /****************************************
00097    * State
00098    ****************************************/
00099   
00100   CloudBuffer clouds_;
00101   CloudConstPtr last_cloud_;
00102 
00103 };
00104   
00105 
00106 template <class T>
00107 T getPrivateParam(const string& name, const T& default_value)
00108 {
00109   ros::NodeHandle nh("~");
00110   T value;
00111   nh.param(name, value, default_value);
00112   return value;
00113 }
00114 
00115 
00116 GridConstructionNode::GridConstructionNode () :
00117   history_length_(getPrivateParam("history_length", 100)), resolution_(getPrivateParam("resolution", 0.1)),
00118   fixed_frame_("odom"), sensor_frame_("base_laser_link"), 
00119   grid_construction_interval_(getPrivateParam("grid_construction_interval", 0.3)),
00120   local_grid_size_(getPrivateParam("local_grid_size", 15.0)),
00121   scan_sub_(nh_.subscribe("base_scan", 1, &GridConstructionNode::scanCallback, this)),
00122   grid_pub_(nh_.advertise<nm::OccupancyGrid>("local_grid", 1)),
00123   build_grid_timer_(nh_.createWallTimer(ros::WallDuration(grid_construction_interval_), 
00124                                         &GridConstructionNode::buildGrid, this)),
00125   clouds_(history_length_)
00126 {
00127 }
00128 
00129 
00130 void GridConstructionNode::scanCallback (const sm::LaserScan& scan)
00131 {
00132   try {
00133 
00134     // We'll need the transform between sensor and fixed frames at the time when the scan was taken
00135     if (!tf_.waitForTransform(fixed_frame_, sensor_frame_, scan.header.stamp, ros::Duration(1.0)))
00136     {
00137       ROS_WARN_STREAM ("Timed out waiting for transform from " << sensor_frame_ << " to "
00138                        << fixed_frame_ << " at " << scan.header.stamp.toSec());
00139       return;
00140     }
00141 
00142     // Figure out current sensor position
00143     tf::Pose identity(tf::createIdentityQuaternion(), btVector3(0, 0, 0));
00144     tf::Stamped<tf::Pose> odom_pose;
00145     tf_.transformPose(fixed_frame_, tf::Stamped<tf::Pose> (identity, ros::Time(), sensor_frame_), odom_pose);
00146 
00147     // Project scan from sensor frame (which varies over time) to odom (which doesn't)
00148     sm::PointCloud fixed_frame_cloud;
00149     laser_geometry::LaserProjection projector_;
00150     projector_.transformLaserScanToPointCloud (fixed_frame_, scan, fixed_frame_cloud, tf_);
00151     
00152     // Now transform back into sensor frame at a single time point
00153     sm::PointCloud sensor_frame_cloud;
00154     tf_.transformPointCloud (sensor_frame_, scan.header.stamp, fixed_frame_cloud, fixed_frame_, 
00155                              sensor_frame_cloud);
00156 
00157     // Construct and save LocalizedCloud
00158     CloudPtr loc_cloud(new gu::LocalizedCloud());
00159     loc_cloud->cloud.points = sensor_frame_cloud.points;
00160     tf::poseTFToMsg(odom_pose, loc_cloud->sensor_pose.pose);
00161     loc_cloud->sensor_pose.header.frame_id = fixed_frame_;
00162     Lock lock(mutex_);
00163     last_cloud_=loc_cloud;
00164   }
00165   catch (tf::LookupException& e) {
00166     ROS_INFO ("Not saving scan due to tf lookup exception");
00167   }
00168 }
00169 
00170 
00171 void GridConstructionNode::buildGrid (const ros::WallTimerEvent& scan)
00172 {
00173   if (last_cloud_) {
00174     {
00175       Lock lock(mutex_);
00176       clouds_.push_back(last_cloud_);
00177       last_cloud_.reset();
00178     }
00179 
00180     ROS_DEBUG_NAMED ("build_grid", "Building grid with %zu scans", clouds_.size());
00181     
00182     // Figure out current position
00183     gm::PoseStamped identity, odom_pose;
00184     identity.pose.orientation = tf::createQuaternionMsgFromYaw(0);
00185     identity.header.frame_id = sensor_frame_;
00186     identity.header.stamp = ros::Time();
00187     tf_.transformPose(fixed_frame_, identity, odom_pose);
00188 
00189     // Set up map dimensions
00190     nm::MapMetaData info;
00191     info.origin.position.x = odom_pose.pose.position.x-local_grid_size_/2;
00192     info.origin.position.y = odom_pose.pose.position.y-local_grid_size_/2;
00193     info.origin.orientation = tf::createQuaternionMsgFromYaw(0);
00194     info.resolution = resolution_;
00195     info.width = local_grid_size_/resolution_;
00196     info.height = local_grid_size_/resolution_;
00197 
00198     gu::OverlayClouds overlay = gu::createCloudOverlay(info, fixed_frame_, 0.1, 10, 2);
00199     vector<CloudConstPtr> clouds(clouds_.begin(), clouds_.end());
00200     BOOST_FOREACH  (CloudConstPtr cloud, clouds_)
00201       gu::addCloud(&overlay, cloud);
00202     nm::OccupancyGrid::ConstPtr grid = gu::getGrid(overlay);
00203 
00204     ROS_DEBUG_NAMED ("build_grid", "Done building grid");
00205     
00206     grid_pub_.publish(grid);
00207   }
00208 }
00209 
00210 } // namespace grid_construction_node
00211 
00212 int main (int argc, char** argv)
00213 {
00214   ros::init(argc, argv, "grid_construction_node");
00215   grid_construction_node::GridConstructionNode node;
00216   ros::spin();
00217   return 0;
00218 }


occupancy_grid_utils
Author(s): Bhaskara Marthi
autogenerated on Tue Jan 7 2014 11:17:09