Takes in point clouds from sensors, transforms them to the desired frame, and stores them.
More...
#include <observation_buffer.h>
|
void | bufferCloud (const sensor_msgs::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 | bufferCloud (const pcl::PointCloud< pcl::PointXYZ > &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. More...
|
|
| ObservationBuffer (std::string topic_name, double observation_keep_time, double expected_update_rate, double min_obstacle_height, double max_obstacle_height, double obstacle_range, double raytrace_range, tf::TransformListener &tf, std::string global_frame, std::string sensor_frame, double tf_tolerance) |
| Constructs an observation buffer. More...
|
|
void | resetLastUpdated () |
| Reset last updated timestamp. More...
|
|
bool | setGlobalFrame (const std::string new_global_frame) |
| Sets the global frame of an observation buffer. This will transform all the currently cached observations to the new global frame. More...
|
|
void | unlock () |
| Lock the observation buffer. More...
|
|
| ~ObservationBuffer () |
| Destructor... cleans up. More...
|
|
Takes in point clouds from sensors, transforms them to the desired frame, and stores them.
Definition at line 61 of file observation_buffer.h.
costmap_2d::ObservationBuffer::ObservationBuffer |
( |
std::string |
topic_name, |
|
|
double |
observation_keep_time, |
|
|
double |
expected_update_rate, |
|
|
double |
min_obstacle_height, |
|
|
double |
max_obstacle_height, |
|
|
double |
obstacle_range, |
|
|
double |
raytrace_range, |
|
|
tf::TransformListener & |
tf, |
|
|
std::string |
global_frame, |
|
|
std::string |
sensor_frame, |
|
|
double |
tf_tolerance |
|
) |
| |
Constructs an observation buffer.
- Parameters
-
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_range | The range to which the sensor should be trusted for inserting obstacles |
raytrace_range | The range to which the sensor should be trusted for raytracing to clear out space |
tf | A reference to a TransformListener |
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.
costmap_2d::ObservationBuffer::~ObservationBuffer |
( |
| ) |
|
void costmap_2d::ObservationBuffer::bufferCloud |
( |
const sensor_msgs::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
- Parameters
-
cloud | The cloud to be buffered |
Definition at line 111 of file observation_buffer.cpp.
void costmap_2d::ObservationBuffer::bufferCloud |
( |
const pcl::PointCloud< pcl::PointXYZ > & |
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
- Parameters
-
cloud | The cloud to be buffered |
Definition at line 129 of file observation_buffer.cpp.
void costmap_2d::ObservationBuffer::getObservations |
( |
std::vector< Observation > & |
observations | ) |
|
Pushes copies of all current observations onto the end of the vector passed in.
- Parameters
-
observations | The vector to be filled |
Definition at line 198 of file observation_buffer.cpp.
bool costmap_2d::ObservationBuffer::isCurrent |
( |
| ) |
const |
Check if the observation buffer is being update at its expected rate.
- Returns
- True if it is being updated at the expected rate, false otherwise
Definition at line 238 of file observation_buffer.cpp.
void costmap_2d::ObservationBuffer::lock |
( |
| ) |
|
|
inline |
void costmap_2d::ObservationBuffer::purgeStaleObservations |
( |
| ) |
|
|
private |
void costmap_2d::ObservationBuffer::resetLastUpdated |
( |
| ) |
|
bool costmap_2d::ObservationBuffer::setGlobalFrame |
( |
const std::string |
new_global_frame | ) |
|
Sets the global frame of an observation buffer. This will transform all the currently cached observations to the new global frame.
- Parameters
-
new_global_frame | The name of the new global frame. |
- Returns
- True if the operation succeeds, false otherwise
Definition at line 66 of file observation_buffer.cpp.
void costmap_2d::ObservationBuffer::unlock |
( |
| ) |
|
|
inline |
const ros::Duration costmap_2d::ObservationBuffer::expected_update_rate_ |
|
private |
std::string costmap_2d::ObservationBuffer::global_frame_ |
|
private |
ros::Time costmap_2d::ObservationBuffer::last_updated_ |
|
private |
boost::recursive_mutex costmap_2d::ObservationBuffer::lock_ |
|
private |
double costmap_2d::ObservationBuffer::max_obstacle_height_ |
|
private |
double costmap_2d::ObservationBuffer::min_obstacle_height_ |
|
private |
const ros::Duration costmap_2d::ObservationBuffer::observation_keep_time_ |
|
private |
std::list<Observation> costmap_2d::ObservationBuffer::observation_list_ |
|
private |
double costmap_2d::ObservationBuffer::obstacle_range_ |
|
private |
double costmap_2d::ObservationBuffer::raytrace_range_ |
|
private |
std::string costmap_2d::ObservationBuffer::sensor_frame_ |
|
private |
double costmap_2d::ObservationBuffer::tf_tolerance_ |
|
private |
std::string costmap_2d::ObservationBuffer::topic_name_ |
|
private |
The documentation for this class was generated from the following files:
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:42