Skip to content
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions nav2_costmap_2d/src/observation_buffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,6 +153,15 @@ void ObservationBuffer::bufferCloud(const sensor_msgs::msg::PointCloud2 & cloud)
modifier.resize(point_count);
observation_cloud.header.stamp = cloud.header.stamp;
observation_cloud.header.frame_id = global_frame_cloud.header.frame_id;
} catch (tf2::ExtrapolationException & ex) {
// if an exception occurs, we need to remove the empty observation from the list
observation_list_.pop_front();
RCLCPP_ERROR(
logger_,
"TF Extrapolation Exception that should never happen for sensor frame: %s, cloud frame: %s, %s",
sensor_frame_.c_str(),
cloud.header.frame_id.c_str(), ex.what());
return;
} catch (tf2::TransformException & ex) {
// if an exception occurs, we need to remove the empty observation from the list
observation_list_.pop_front();
Expand Down