RAPP Platform  v0.6.0
RAPP Platform is a collection of ROS nodes and back-end processes that aim to deliver ready-to-use generic services to robots
 All Classes Namespaces Files Functions Variables Macros
observation_buffer.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  *********************************************************************/
37 #include <costmap_2d/observation_buffer.h>
38 
39 #include <pcl/point_types.h>
40 #include <pcl_ros/transforms.h>
41 #include <pcl/conversions.h>
42 #include <pcl/PCLPointCloud2.h>
43 
44 #include <pcl_conversions/pcl_conversions.h>
45 
46 using namespace std;
47 using namespace tf;
48 
49 namespace costmap_2d
50 {
51 ObservationBuffer::ObservationBuffer(string topic_name, double observation_keep_time, double expected_update_rate,
52  double min_obstacle_height, double max_obstacle_height, double obstacle_range,
53  double raytrace_range, TransformListener& tf, string global_frame,
54  string sensor_frame, double tf_tolerance) :
55  tf_(tf), observation_keep_time_(observation_keep_time), expected_update_rate_(expected_update_rate), last_updated_(
56  ros::Time::now()), global_frame_(global_frame), sensor_frame_(sensor_frame), topic_name_(topic_name), min_obstacle_height_(
57  min_obstacle_height), max_obstacle_height_(max_obstacle_height), obstacle_range_(obstacle_range), raytrace_range_(
58  raytrace_range), tf_tolerance_(tf_tolerance)
59 {
60 }
61 
62 ObservationBuffer::~ObservationBuffer()
63 {
64 }
65 
66 bool ObservationBuffer::setGlobalFrame(const std::string new_global_frame)
67 {
68  ros::Time transform_time = ros::Time::now();
69  std::string tf_error;
70 
71  if (!tf_.waitForTransform(new_global_frame, global_frame_, transform_time, ros::Duration(tf_tolerance_),
72  ros::Duration(0.01), &tf_error))
73  {
74  ROS_ERROR("Transform between %s and %s with tolerance %.2f failed: %s.", new_global_frame.c_str(),
75  global_frame_.c_str(), tf_tolerance_, tf_error.c_str());
76  return false;
77  }
78 
79  list<Observation>::iterator obs_it;
80  for (obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it)
81  {
82  try
83  {
84  Observation& obs = *obs_it;
85 
86  geometry_msgs::PointStamped origin;
87  origin.header.frame_id = global_frame_;
88  origin.header.stamp = transform_time;
89  origin.point = obs.origin_;
90 
91  //we need to transform the origin of the observation to the new global frame
92  tf_.transformPoint(new_global_frame, origin, origin);
93  obs.origin_ = origin.point;
94 
95  //we also need to transform the cloud of the observation to the new global frame
96  pcl_ros::transformPointCloud(new_global_frame, *obs.cloud_, *obs.cloud_, tf_);
97 
98  }
99  catch (TransformException& ex)
100  {
101  ROS_ERROR("TF Error attempting to transform an observation from %s to %s: %s", global_frame_.c_str(),
102  new_global_frame.c_str(), ex.what());
103  return false;
104  }
105  }
106 
107  //now we need to update our global_frame member
108  global_frame_ = new_global_frame;
109  return true;
110 }
111 
112 void ObservationBuffer::bufferCloud(const sensor_msgs::PointCloud2& cloud)
113 {
114  try
115  {
116  pcl::PCLPointCloud2 pcl_pc2;
117  pcl_conversions::toPCL(cloud, pcl_pc2);
118  // Actually convert the PointCloud2 message into a type we can reason about
119  pcl::PointCloud < pcl::PointXYZ > pcl_cloud;
120  pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
121  bufferCloud (pcl_cloud);
122  }
123  catch (pcl::PCLException& ex)
124  {
125  ROS_ERROR("Failed to convert a message to a pcl type, dropping observation: %s", ex.what());
126  return;
127  }
128 }
129 
130 void ObservationBuffer::bufferCloud(const pcl::PointCloud<pcl::PointXYZ>& cloud)
131 {
132  Stamped < tf::Vector3 > global_origin;
133 
134  //create a new observation on the list to be populated
135  observation_list_.push_front(Observation());
136 
137  //check whether the origin frame has been set explicitly or whether we should get it from the cloud
138  string origin_frame = sensor_frame_ == "" ? cloud.header.frame_id : sensor_frame_;
139 
140  try
141  {
142  //given these observations come from sensors... we'll need to store the origin pt of the sensor
143  Stamped < tf::Vector3 > local_origin(tf::Vector3(0, 0, 0), pcl_conversions::fromPCL(cloud.header).stamp, origin_frame);
144  tf_.waitForTransform(global_frame_, local_origin.frame_id_, local_origin.stamp_, ros::Duration(0.5));
145  tf_.transformPoint(global_frame_, local_origin, global_origin);
146  observation_list_.front().origin_.x = global_origin.getX();
147  observation_list_.front().origin_.y = global_origin.getY();
148  observation_list_.front().origin_.z = global_origin.getZ();
149 
150  //make sure to pass on the raytrace/obstacle range of the observation buffer to the observations the costmap will see
151  observation_list_.front().raytrace_range_ = raytrace_range_;
152  observation_list_.front().obstacle_range_ = obstacle_range_;
153 
154  pcl::PointCloud < pcl::PointXYZ > global_frame_cloud;
155 
156  //transform the point cloud
157  pcl_ros::transformPointCloud(global_frame_, cloud, global_frame_cloud, tf_);
158  global_frame_cloud.header.stamp = cloud.header.stamp;
159 
160  //now we need to remove observations from the cloud that are below or above our height thresholds
161  pcl::PointCloud < pcl::PointXYZ > &observation_cloud = *(observation_list_.front().cloud_);
162  unsigned int cloud_size = global_frame_cloud.points.size();
163  observation_cloud.points.resize(cloud_size);
164  unsigned int point_count = 0;
165 
166  //copy over the points that are within our height bounds
167  for (unsigned int i = 0; i < cloud_size; ++i)
168  {
169  if (global_frame_cloud.points[i].z <= max_obstacle_height_
170  && global_frame_cloud.points[i].z >= min_obstacle_height_)
171  {
172  observation_cloud.points[point_count++] = global_frame_cloud.points[i];
173  }
174  }
175 
176  //resize the cloud for the number of legal points
177  observation_cloud.points.resize(point_count);
178  observation_cloud.header.stamp = cloud.header.stamp;
179  observation_cloud.header.frame_id = global_frame_cloud.header.frame_id;
180  }
181  catch (TransformException& ex)
182  {
183  //if an exception occurs, we need to remove the empty observation from the list
184  observation_list_.pop_front();
185  ROS_ERROR("TF Exception that should never happen for sensor frame: %s, cloud frame: %s, %s", sensor_frame_.c_str(),
186  cloud.header.frame_id.c_str(), ex.what());
187  return;
188  }
189 
190  //if the update was successful, we want to update the last updated time
191  last_updated_ = ros::Time::now();
192 
193  //we'll also remove any stale observations from the list
194  purgeStaleObservations();
195 
196 }
197 
198 //returns a copy of the observations
199 void ObservationBuffer::getObservations(vector<Observation>& observations)
200 {
201  //first... let's make sure that we don't have any stale observations
202  purgeStaleObservations();
203 
204  //now we'll just copy the observations for the caller
205  list<Observation>::iterator obs_it;
206  for (obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it)
207  {
208  observations.push_back(*obs_it);
209  }
210 
211 }
212 
213 void ObservationBuffer::purgeStaleObservations()
214 {
215  if (!observation_list_.empty())
216  {
217  list<Observation>::iterator obs_it = observation_list_.begin();
218  //if we're keeping observations for no time... then we'll only keep one observation
219  if (observation_keep_time_ == ros::Duration(0.0))
220  {
221  observation_list_.erase(++obs_it, observation_list_.end());
222  return;
223  }
224 
225  //otherwise... we'll have to loop through the observations to see which ones are stale
226  for (obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it)
227  {
228  Observation& obs = *obs_it;
229  //check if the observation is out of date... and if it is, remove it and those that follow from the list
230  ros::Duration time_diff = last_updated_ - pcl_conversions::fromPCL(obs.cloud_->header).stamp;
231  if ((last_updated_ - pcl_conversions::fromPCL(obs.cloud_->header).stamp) > observation_keep_time_)
232  {
233  observation_list_.erase(obs_it, observation_list_.end());
234  return;
235  }
236  }
237  }
238 }
239 
240 bool ObservationBuffer::isCurrent() const
241 {
242  if (expected_update_rate_ == ros::Duration(0.0))
243  return true;
244 
245  bool current = (ros::Time::now() - last_updated_).toSec() <= expected_update_rate_.toSec();
246  if (!current)
247  {
248  ROS_WARN(
249  "The %s observation buffer has not been updated for %.2f seconds, and it should be updated every %.2f seconds.",
250  topic_name_.c_str(), (ros::Time::now() - last_updated_).toSec(), expected_update_rate_.toSec());
251  }
252  return current;
253 }
254 
255 void ObservationBuffer::resetLastUpdated()
256 {
257  last_updated_ = ros::Time::now();
258 }
259 }
260 
list origin
Definition: crop_map.py:62