37 #ifndef NAV2_COSTMAP_2D__OBSERVATION_BUFFER_HPP_
38 #define NAV2_COSTMAP_2D__OBSERVATION_BUFFER_HPP_
44 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
45 #include "rclcpp/time.hpp"
46 #include "tf2_ros/buffer.h"
47 #include "tf2_sensor_msgs/tf2_sensor_msgs.hpp"
48 #include "sensor_msgs/msg/point_cloud2.hpp"
49 #include "nav2_costmap_2d/observation.hpp"
50 #include "nav2_util/lifecycle_node.hpp"
79 const nav2_util::LifecycleNode::WeakPtr & parent,
80 std::string topic_name,
81 double observation_keep_time,
82 double expected_update_rate,
83 double min_obstacle_height,
double max_obstacle_height,
double obstacle_max_range,
84 double obstacle_min_range,
85 double raytrace_max_range,
double raytrace_min_range, tf2_ros::Buffer & tf2_buffer,
86 std::string global_frame,
87 std::string sensor_frame,
88 tf2::Duration tf_tolerance);
100 void bufferCloud(
const sensor_msgs::msg::PointCloud2 & cloud);
139 void purgeStaleObservations();
141 rclcpp::Clock::SharedPtr clock_;
142 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_costmap_2d")};
143 tf2_ros::Buffer & tf2_buffer_;
144 const rclcpp::Duration observation_keep_time_;
145 const rclcpp::Duration expected_update_rate_;
146 rclcpp::Time last_updated_;
147 std::string global_frame_;
148 std::string sensor_frame_;
149 std::list<Observation> observation_list_;
150 std::string topic_name_;
151 double min_obstacle_height_, max_obstacle_height_;
152 std::recursive_mutex lock_;
153 double obstacle_max_range_, obstacle_min_range_, raytrace_max_range_, raytrace_min_range_;
154 tf2::Duration tf_tolerance_;
Takes in point clouds from sensors, transforms them to the desired frame, and stores them.
ObservationBuffer(const nav2_util::LifecycleNode::WeakPtr &parent, std::string topic_name, double observation_keep_time, double expected_update_rate, double min_obstacle_height, double max_obstacle_height, double obstacle_max_range, double obstacle_min_range, double raytrace_max_range, double raytrace_min_range, tf2_ros::Buffer &tf2_buffer, std::string global_frame, std::string sensor_frame, tf2::Duration tf_tolerance)
Constructs an observation buffer.
~ObservationBuffer()
Destructor... cleans up.
void unlock()
Lock the observation buffer.
void lock()
Lock the observation buffer.
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.