observation_buffer.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2008, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Eitan Marder-Eppstein
00036 *********************************************************************/
00037 #include <costmap_2d/observation_buffer.h>
00038 
00039 using namespace std;
00040 using namespace tf;
00041 
00042 namespace costmap_2d {
00043   ObservationBuffer::ObservationBuffer(string topic_name, double observation_keep_time, double expected_update_rate, 
00044       double min_obstacle_height, double max_obstacle_height, double obstacle_range, double raytrace_range,
00045       TransformListener& tf, string global_frame, string sensor_frame, double tf_tolerance) : tf_(tf),
00046   observation_keep_time_(observation_keep_time), expected_update_rate_(expected_update_rate), last_updated_(ros::Time::now()),
00047   global_frame_(global_frame), sensor_frame_(sensor_frame), topic_name_(topic_name), min_obstacle_height_(min_obstacle_height),
00048   max_obstacle_height_(max_obstacle_height), obstacle_range_(obstacle_range), raytrace_range_(raytrace_range), tf_tolerance_(tf_tolerance)
00049   {
00050   }
00051 
00052   ObservationBuffer::~ObservationBuffer(){}
00053 
00054   bool ObservationBuffer::setGlobalFrame(const std::string new_global_frame){
00055     ros::Time transform_time = ros::Time::now();
00056     std::string tf_error;
00057 
00058     if(!tf_.waitForTransform(new_global_frame, global_frame_, transform_time, ros::Duration(tf_tolerance_), ros::Duration(0.01), &tf_error)){
00059       ROS_ERROR("Transform between %s and %s with tolerance %.2f failed: %s.", new_global_frame.c_str(), global_frame_.c_str(), tf_tolerance_, tf_error.c_str());
00060       return false;
00061     }
00062 
00063     list<Observation>::iterator obs_it;
00064     for(obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it){
00065       try{
00066         Observation& obs = *obs_it;
00067 
00068         geometry_msgs::PointStamped origin;
00069         origin.header.frame_id = global_frame_;
00070         origin.header.stamp = transform_time;
00071         origin.point = obs.origin_;
00072 
00073         //we need to transform the origin of the observation to the new global frame
00074         tf_.transformPoint(new_global_frame, origin, origin);
00075         obs.origin_ = origin.point;
00076 
00077         //we also need to transform the cloud of the observation to the new global frame
00078         pcl_ros::transformPointCloud(new_global_frame, obs.cloud_, obs.cloud_, tf_);
00079 
00080       }
00081       catch(TransformException& ex){
00082         ROS_ERROR("TF Error attempting to transform an observation from %s to %s: %s", global_frame_.c_str(), 
00083             new_global_frame.c_str(), ex.what());
00084         return false;
00085       }
00086     }
00087 
00088     //now we need to update our global_frame member
00089     global_frame_ = new_global_frame;
00090     return true;
00091   }
00092 
00093   void ObservationBuffer::bufferCloud(const sensor_msgs::PointCloud2& cloud){
00094     try {
00095       //actually convert the PointCloud2 message into a type we can reason about
00096       pcl::PointCloud<pcl::PointXYZ> pcl_cloud;
00097       pcl::fromROSMsg(cloud, pcl_cloud);
00098       bufferCloud(pcl_cloud);
00099     }
00100     catch(pcl::PCLException& ex){
00101       ROS_ERROR("Failed to convert a message to a pcl type, dropping observation: %s", ex.what());
00102       return;
00103     }
00104   }
00105 
00106   void ObservationBuffer::bufferCloud(const pcl::PointCloud<pcl::PointXYZ>& cloud){
00107     Stamped<tf::Vector3> global_origin;
00108 
00109     //create a new observation on the list to be populated
00110     observation_list_.push_front(Observation());
00111 
00112     //check whether the origin frame has been set explicitly or whether we should get it from the cloud
00113     string origin_frame = sensor_frame_ == "" ? cloud.header.frame_id : sensor_frame_;
00114 
00115     try{
00116       //given these observations come from sensors... we'll need to store the origin pt of the sensor
00117       Stamped<tf::Vector3> local_origin(tf::Vector3(0, 0, 0), cloud.header.stamp, origin_frame);
00118       tf_.transformPoint(global_frame_, local_origin, global_origin);
00119       observation_list_.front().origin_.x = global_origin.getX();
00120       observation_list_.front().origin_.y = global_origin.getY();
00121       observation_list_.front().origin_.z = global_origin.getZ();
00122 
00123       //make sure to pass on the raytrace/obstacle range of the observation buffer to the observations the costmap will see
00124       observation_list_.front().raytrace_range_ = raytrace_range_;
00125       observation_list_.front().obstacle_range_ = obstacle_range_;
00126 
00127       pcl::PointCloud<pcl::PointXYZ> global_frame_cloud;
00128 
00129       //transform the point cloud
00130       pcl_ros::transformPointCloud(global_frame_, cloud, global_frame_cloud, tf_);
00131       global_frame_cloud.header.stamp = cloud.header.stamp;
00132 
00133       //now we need to remove observations from the cloud that are below or above our height thresholds
00134       pcl::PointCloud<pcl::PointXYZ>& observation_cloud = observation_list_.front().cloud_;
00135       unsigned int cloud_size = global_frame_cloud.points.size();
00136       observation_cloud.points.resize(cloud_size);
00137       unsigned int point_count = 0;
00138       
00139       //copy over the points that are within our height bounds
00140       for(unsigned int i = 0; i < cloud_size; ++i){
00141         if(global_frame_cloud.points[i].z <= max_obstacle_height_ && global_frame_cloud.points[i].z >= min_obstacle_height_){
00142           observation_cloud.points[point_count++] = global_frame_cloud.points[i];
00143         }
00144       }
00145 
00146       //resize the cloud for the number of legal points
00147       observation_cloud.points.resize(point_count);
00148       observation_cloud.header.stamp = cloud.header.stamp;
00149       observation_cloud.header.frame_id = global_frame_cloud.header.frame_id;
00150     }
00151     catch(TransformException& ex){
00152       //if an exception occurs, we need to remove the empty observation from the list
00153       observation_list_.pop_front();
00154       ROS_ERROR("TF Exception that should never happen for sensor frame: %s, cloud frame: %s, %s", sensor_frame_.c_str(), 
00155           cloud.header.frame_id.c_str(), ex.what());
00156       return;
00157     }
00158 
00159     //if the update was successful, we want to update the last updated time
00160     last_updated_ = ros::Time::now();
00161 
00162     //we'll also remove any stale observations from the list
00163     purgeStaleObservations();
00164 
00165   }
00166 
00167   //returns a copy of the observations
00168   void ObservationBuffer::getObservations(vector<Observation>& observations){
00169     //first... let's make sure that we don't have any stale observations
00170     purgeStaleObservations();
00171 
00172     //now we'll just copy the observations for the caller
00173     list<Observation>::iterator obs_it;
00174     for(obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it){
00175       observations.push_back(*obs_it);
00176     }
00177 
00178   }
00179 
00180   void ObservationBuffer::purgeStaleObservations(){
00181     if(!observation_list_.empty()){
00182       list<Observation>::iterator obs_it = observation_list_.begin();
00183       //if we're keeping observations for no time... then we'll only keep one observation
00184       if(observation_keep_time_ == ros::Duration(0.0)){
00185         observation_list_.erase(++obs_it, observation_list_.end());
00186         return;
00187       }
00188 
00189       //otherwise... we'll have to loop through the observations to see which ones are stale
00190       for(obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it){
00191         Observation& obs = *obs_it;
00192         //check if the observation is out of date... and if it is, remove it and those that follow from the list
00193         ros::Duration time_diff = last_updated_ - obs.cloud_.header.stamp;
00194         if((last_updated_ - obs.cloud_.header.stamp) > observation_keep_time_){
00195           observation_list_.erase(obs_it, observation_list_.end());
00196           return;
00197         }
00198       }
00199     }
00200   }
00201 
00202   bool ObservationBuffer::isCurrent() const {
00203     if(expected_update_rate_ == ros::Duration(0.0))
00204       return true;
00205 
00206     bool current = (ros::Time::now() - last_updated_).toSec() <= expected_update_rate_.toSec();
00207     if(!current){
00208       ROS_WARN("The %s observation buffer has not been updated for %.2f seconds, and it should be updated every %.2f seconds.", topic_name_.c_str(),
00209           (ros::Time::now() - last_updated_).toSec(), expected_update_rate_.toSec());
00210     }
00211     return current;
00212   }
00213 
00214   void ObservationBuffer::resetLastUpdated ()
00215   {
00216     last_updated_ = ros::Time::now();
00217   }
00218 };


costmap_2d
Author(s): Eitan Marder-Eppstein
autogenerated on Sat Dec 28 2013 17:13:40