Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
Takes in point clouds from sensors, transforms them to the desired frame, and stores them. More...
#include <nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp>
Public Member Functions | |
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. More... | |
~ObservationBuffer () | |
Destructor... cleans up. | |
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 sure the transform is available... ie they should use a MessageNotifier More... | |
void | getObservations (std::vector< Observation > &observations) |
Pushes copies of all current observations onto the end of the vector passed in. More... | |
bool | isCurrent () const |
Check if the observation buffer is being update at its expected rate. More... | |
void | lock () |
Lock the observation buffer. | |
void | unlock () |
Lock the observation buffer. | |
void | resetLastUpdated () |
Reset last updated timestamp. | |
Takes in point clouds from sensors, transforms them to the desired frame, and stores them.
Definition at line 59 of file observation_buffer.hpp.
nav2_costmap_2d::ObservationBuffer::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.
topic_name | The topic of the observations, used as an identifier for error and warning messages |
observation_keep_time | Defines the persistence of observations in seconds, 0 means only keep the latest |
expected_update_rate | How often this buffer is expected to be updated, 0 means there is no limit |
min_obstacle_height | The minimum height of a hitpoint to be considered legal |
max_obstacle_height | The minimum height of a hitpoint to be considered legal |
obstacle_max_range | The range to which the sensor should be trusted for inserting obstacles |
obstacle_min_range | The range from which the sensor should be trusted for inserting obstacles |
raytrace_max_range | The range to which the sensor should be trusted for raytracing to clear out space |
raytrace_min_range | The range from which the sensor should be trusted for raytracing to clear out space |
tf2_buffer | A reference to a tf2 Buffer |
global_frame | The frame to transform PointClouds into |
sensor_frame | The frame of the origin of the sensor, can be left blank to be read from the messages |
tf_tolerance | The amount of time to wait for a transform to be available when setting a new global frame |
Definition at line 51 of file observation_buffer.cpp.
void nav2_costmap_2d::ObservationBuffer::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 sure the transform is available... ie they should use a MessageNotifier
cloud | The cloud to be buffered |
Definition at line 83 of file observation_buffer.cpp.
void nav2_costmap_2d::ObservationBuffer::getObservations | ( | std::vector< Observation > & | observations | ) |
Pushes copies of all current observations onto the end of the vector passed in.
observations | The vector to be filled |
Definition at line 175 of file observation_buffer.cpp.
bool nav2_costmap_2d::ObservationBuffer::isCurrent | ( | ) | const |
Check if the observation buffer is being update at its expected rate.
Definition at line 212 of file observation_buffer.cpp.