37 #include <costmap_2d/observation_buffer.h>
39 #include <pcl/point_types.h>
40 #include <pcl_ros/transforms.h>
41 #include <pcl/conversions.h>
42 #include <pcl/PCLPointCloud2.h>
44 #include <pcl_conversions/pcl_conversions.h>
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)
62 ObservationBuffer::~ObservationBuffer()
66 bool ObservationBuffer::setGlobalFrame(
const std::string new_global_frame)
68 ros::Time transform_time = ros::Time::now();
71 if (!tf_.waitForTransform(new_global_frame, global_frame_, transform_time, ros::Duration(tf_tolerance_),
72 ros::Duration(0.01), &tf_error))
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());
79 list<Observation>::iterator obs_it;
80 for (obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it)
84 Observation& obs = *obs_it;
86 geometry_msgs::PointStamped
origin;
87 origin.header.frame_id = global_frame_;
88 origin.header.stamp = transform_time;
89 origin.point = obs.origin_;
92 tf_.transformPoint(new_global_frame, origin, origin);
93 obs.origin_ = origin.point;
96 pcl_ros::transformPointCloud(new_global_frame, *obs.cloud_, *obs.cloud_, tf_);
99 catch (TransformException& ex)
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());
108 global_frame_ = new_global_frame;
112 void ObservationBuffer::bufferCloud(
const sensor_msgs::PointCloud2& cloud)
116 pcl::PCLPointCloud2 pcl_pc2;
117 pcl_conversions::toPCL(cloud, pcl_pc2);
119 pcl::PointCloud < pcl::PointXYZ > pcl_cloud;
120 pcl::fromPCLPointCloud2(pcl_pc2, pcl_cloud);
121 bufferCloud (pcl_cloud);
123 catch (pcl::PCLException& ex)
125 ROS_ERROR(
"Failed to convert a message to a pcl type, dropping observation: %s", ex.what());
130 void ObservationBuffer::bufferCloud(
const pcl::PointCloud<pcl::PointXYZ>& cloud)
132 Stamped < tf::Vector3 > global_origin;
135 observation_list_.push_front(Observation());
138 string origin_frame = sensor_frame_ ==
"" ? cloud.header.frame_id : sensor_frame_;
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();
151 observation_list_.front().raytrace_range_ = raytrace_range_;
152 observation_list_.front().obstacle_range_ = obstacle_range_;
154 pcl::PointCloud < pcl::PointXYZ > global_frame_cloud;
157 pcl_ros::transformPointCloud(global_frame_, cloud, global_frame_cloud, tf_);
158 global_frame_cloud.header.stamp = cloud.header.stamp;
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;
167 for (
unsigned int i = 0; i < cloud_size; ++i)
169 if (global_frame_cloud.points[i].z <= max_obstacle_height_
170 && global_frame_cloud.points[i].z >= min_obstacle_height_)
172 observation_cloud.points[point_count++] = global_frame_cloud.points[i];
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;
181 catch (TransformException& ex)
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());
191 last_updated_ = ros::Time::now();
194 purgeStaleObservations();
199 void ObservationBuffer::getObservations(vector<Observation>& observations)
202 purgeStaleObservations();
205 list<Observation>::iterator obs_it;
206 for (obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it)
208 observations.push_back(*obs_it);
213 void ObservationBuffer::purgeStaleObservations()
215 if (!observation_list_.empty())
217 list<Observation>::iterator obs_it = observation_list_.begin();
219 if (observation_keep_time_ == ros::Duration(0.0))
221 observation_list_.erase(++obs_it, observation_list_.end());
226 for (obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it)
228 Observation& obs = *obs_it;
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_)
233 observation_list_.erase(obs_it, observation_list_.end());
240 bool ObservationBuffer::isCurrent()
const
242 if (expected_update_rate_ == ros::Duration(0.0))
245 bool current = (ros::Time::now() - last_updated_).toSec() <= expected_update_rate_.toSec();
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());
255 void ObservationBuffer::resetLastUpdated()
257 last_updated_ = ros::Time::now();