37 #include "nav2_costmap_2d/observation_buffer.hpp"
45 #include "tf2/convert.h"
46 #include "sensor_msgs/point_cloud2_iterator.hpp"
47 using namespace std::chrono_literals;
51 ObservationBuffer::ObservationBuffer(
52 const nav2_util::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)
73 auto node = parent.lock();
74 clock_ = node->get_clock();
75 logger_ = node->get_logger();
76 last_updated_ = node->now();
85 geometry_msgs::msg::PointStamped global_origin;
92 std::string origin_frame = sensor_frame_ ==
"" ? cloud.header.frame_id : sensor_frame_;
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_);
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_;
113 sensor_msgs::msg::PointCloud2 global_frame_cloud;
116 tf2_buffer_.transform(cloud, global_frame_cloud, global_frame_, tf_tolerance_);
117 global_frame_cloud.header.stamp = cloud.header.stamp;
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;
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;
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)
143 if ((*iter_z) <= max_obstacle_height_ &&
144 (*iter_z) >= min_obstacle_height_)
146 std::copy(iter_global, iter_global + global_frame_cloud.point_step, iter_obs);
147 iter_obs += global_frame_cloud.point_step;
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) {
158 observation_list_.pop_front();
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());
168 last_updated_ = clock_->now();
171 purgeStaleObservations();
178 purgeStaleObservations();
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);
187 void ObservationBuffer::purgeStaleObservations()
189 if (!observation_list_.empty()) {
190 std::list<Observation>::iterator obs_it = observation_list_.begin();
192 if (observation_keep_time_ == rclcpp::Duration(0.0s)) {
193 observation_list_.erase(++obs_it, observation_list_.end());
198 for (obs_it = observation_list_.begin(); obs_it != observation_list_.end(); ++obs_it) {
199 Observation & obs = *obs_it;
202 if ((clock_->now() - obs.cloud_->header.stamp) >
203 observation_keep_time_)
205 observation_list_.erase(obs_it, observation_list_.end());
214 if (expected_update_rate_ == rclcpp::Duration(0.0s)) {
218 bool current = (clock_->now() - last_updated_) <=
219 expected_update_rate_;
223 "The %s observation buffer has not been updated for %.2f seconds, "
224 "and it should be updated every %.2f seconds.",
226 (clock_->now() - last_updated_).seconds(),
227 expected_update_rate_.seconds());
234 last_updated_ = clock_->now();
~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.