Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
observation_buffer.cpp
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 "nav2_costmap_2d/observation_buffer.hpp"
38 
39 #include <algorithm>
40 #include <list>
41 #include <string>
42 #include <vector>
43 #include <chrono>
44 
45 #include "tf2/convert.hpp"
46 #include "sensor_msgs/point_cloud2_iterator.hpp"
47 using namespace std::chrono_literals;
48 
49 namespace nav2_costmap_2d
50 {
51 ObservationBuffer::ObservationBuffer(
52  const nav2::LifecycleNode::WeakPtr & parent,
53  std::string topic_name,
54  double observation_keep_time,
55  double expected_update_rate,
56  double min_obstacle_height, double max_obstacle_height, double obstacle_max_range,
57  double obstacle_min_range,
58  double raytrace_max_range, double raytrace_min_range, tf2_ros::Buffer & tf2_buffer,
59  std::string global_frame,
60  std::string sensor_frame,
61  tf2::Duration tf_tolerance)
62 : tf2_buffer_(tf2_buffer),
63  observation_keep_time_(rclcpp::Duration::from_seconds(observation_keep_time)),
64  expected_update_rate_(rclcpp::Duration::from_seconds(expected_update_rate)),
65  global_frame_(global_frame),
66  sensor_frame_(sensor_frame),
67  topic_name_(topic_name),
68  min_obstacle_height_(min_obstacle_height), max_obstacle_height_(max_obstacle_height),
69  obstacle_max_range_(obstacle_max_range), obstacle_min_range_(obstacle_min_range),
70  raytrace_max_range_(raytrace_max_range), raytrace_min_range_(
71  raytrace_min_range), tf_tolerance_(tf_tolerance)
72 {
73  auto node = parent.lock();
74  clock_ = node->get_clock();
75  logger_ = node->get_logger();
76  last_updated_ = node->now();
77 }
78 
80 {
81 }
82 
83 void ObservationBuffer::bufferCloud(const sensor_msgs::msg::PointCloud2 & cloud)
84 {
85  geometry_msgs::msg::PointStamped global_origin;
86 
87  // create a new observation on the list to be populated
88  observation_list_.push_front(Observation());
89 
90  // check whether the origin frame has been set explicitly
91  // or whether we should get it from the cloud
92  std::string origin_frame = sensor_frame_ == "" ? cloud.header.frame_id : sensor_frame_;
93 
94  try {
95  // given these observations come from sensors...
96  // we'll need to store the origin pt of the sensor
97  geometry_msgs::msg::PointStamped local_origin;
98  local_origin.header.stamp = cloud.header.stamp;
99  local_origin.header.frame_id = origin_frame;
100  local_origin.point.x = 0;
101  local_origin.point.y = 0;
102  local_origin.point.z = 0;
103  tf2_buffer_.transform(local_origin, global_origin, global_frame_, tf_tolerance_);
104  tf2::convert(global_origin.point, observation_list_.front().origin_);
105 
106  // make sure to pass on the raytrace/obstacle range
107  // of the observation buffer to the observations
108  observation_list_.front().raytrace_max_range_ = raytrace_max_range_;
109  observation_list_.front().raytrace_min_range_ = raytrace_min_range_;
110  observation_list_.front().obstacle_max_range_ = obstacle_max_range_;
111  observation_list_.front().obstacle_min_range_ = obstacle_min_range_;
112 
113  sensor_msgs::msg::PointCloud2 global_frame_cloud;
114 
115  // transform the point cloud
116  tf2_buffer_.transform(cloud, global_frame_cloud, global_frame_, tf_tolerance_);
117  global_frame_cloud.header.stamp = cloud.header.stamp;
118 
119  // now we need to remove observations from the cloud that are below
120  // or above our height thresholds
121  sensor_msgs::msg::PointCloud2 & observation_cloud = *(observation_list_.front().cloud_);
122  observation_cloud.height = global_frame_cloud.height;
123  observation_cloud.width = global_frame_cloud.width;
124  observation_cloud.fields = global_frame_cloud.fields;
125  observation_cloud.is_bigendian = global_frame_cloud.is_bigendian;
126  observation_cloud.point_step = global_frame_cloud.point_step;
127  observation_cloud.row_step = global_frame_cloud.row_step;
128  observation_cloud.is_dense = global_frame_cloud.is_dense;
129 
130  unsigned int cloud_size = global_frame_cloud.height * global_frame_cloud.width;
131  sensor_msgs::PointCloud2Modifier modifier(observation_cloud);
132  modifier.resize(cloud_size);
133  unsigned int point_count = 0;
134 
135  // copy over the points that are within our height bounds
136  sensor_msgs::PointCloud2Iterator<float> iter_z(global_frame_cloud, "z");
137  std::vector<unsigned char>::const_iterator iter_global = global_frame_cloud.data.begin(),
138  iter_global_end = global_frame_cloud.data.end();
139  std::vector<unsigned char>::iterator iter_obs = observation_cloud.data.begin();
140  for (; iter_global != iter_global_end; ++iter_z, iter_global +=
141  global_frame_cloud.point_step)
142  {
143  if ((*iter_z) <= max_obstacle_height_ &&
144  (*iter_z) >= min_obstacle_height_)
145  {
146  std::copy(iter_global, iter_global + global_frame_cloud.point_step, iter_obs);
147  iter_obs += global_frame_cloud.point_step;
148  ++point_count;
149  }
150  }
151 
152  // resize the cloud for the number of legal points
153  modifier.resize(point_count);
154  observation_cloud.header.stamp = cloud.header.stamp;
155  observation_cloud.header.frame_id = global_frame_cloud.header.frame_id;
156  } catch (tf2::TransformException & ex) {
157  // if an exception occurs, we need to remove the empty observation from the list
158  observation_list_.pop_front();
159  RCLCPP_ERROR(
160  logger_,
161  "TF Exception that should never happen for sensor frame: %s, cloud frame: %s, %s",
162  sensor_frame_.c_str(),
163  cloud.header.frame_id.c_str(), ex.what());
164  return;
165  }
166 
167  // if the update was successful, we want to update the last updated time
168  last_updated_ = clock_->now();
169 
170  // we'll also remove any stale observations from the list
171  purgeStaleObservations();
172 }
173 
174 // returns a copy of the observations
175 void ObservationBuffer::getObservations(std::vector<Observation> & observations)
176 {
177  // first... let's make sure that we don't have any stale observations
178  purgeStaleObservations();
179 
180  // now we'll just copy the observations for the caller
181  std::list<Observation>::iterator obs_it;
182  for (obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it) {
183  observations.push_back(*obs_it);
184  }
185 }
186 
187 void ObservationBuffer::purgeStaleObservations()
188 {
189  if (!observation_list_.empty()) {
190  std::list<Observation>::iterator obs_it = observation_list_.begin();
191  // if we're keeping observations for no time... then we'll only keep one observation
192  if (observation_keep_time_ == rclcpp::Duration(0.0s)) {
193  observation_list_.erase(++obs_it, observation_list_.end());
194  return;
195  }
196 
197  // otherwise... we'll have to loop through the observations to see which ones are stale
198  for (obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it) {
199  Observation & obs = *obs_it;
200  // check if the observation is out of date... and if it is,
201  // remove it and those that follow from the list
202  if ((clock_->now() - obs.cloud_->header.stamp) >
203  observation_keep_time_)
204  {
205  observation_list_.erase(obs_it, observation_list_.end());
206  return;
207  }
208  }
209  }
210 }
211 
213 {
214  if (expected_update_rate_ == rclcpp::Duration(0.0s)) {
215  return true;
216  }
217 
218  bool current = (clock_->now() - last_updated_) <=
219  expected_update_rate_;
220  if (!current) {
221  RCLCPP_WARN(
222  logger_,
223  "The %s observation buffer has not been updated for %.2f seconds, "
224  "and it should be updated every %.2f seconds.",
225  topic_name_.c_str(),
226  (clock_->now() - last_updated_).seconds(),
227  expected_update_rate_.seconds());
228  }
229  return current;
230 }
231 
233 {
234  last_updated_ = clock_->now();
235 }
236 } // namespace nav2_costmap_2d
~ObservationBuffer()
Destructor... cleans up.
bool isCurrent() const
Check if the observation buffer is being update at its expected rate.
void getObservations(std::vector< Observation > &observations)
Pushes copies of all current observations onto the end of the vector passed in.
void bufferCloud(const sensor_msgs::msg::PointCloud2 &cloud)
Transforms a PointCloud to the global frame and buffers it Note: The burden is on the user to make su...
void resetLastUpdated()
Reset last updated timestamp.
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.hpp:47