Public Member Functions | Private Member Functions | Private Attributes | List of all members
costmap_2d::ObservationBuffer Class Reference

Takes in point clouds from sensors, transforms them to the desired frame, and stores them. More...

#include <observation_buffer.h>

Public Member Functions

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...
 

Private Member Functions

void purgeStaleObservations ()
 Removes any stale observations from the buffer list. More...
 

Private Attributes

const ros::Duration expected_update_rate_
 
std::string global_frame_
 
ros::Time last_updated_
 
boost::recursive_mutex lock_
 A lock for accessing data in callbacks safely. More...
 
double max_obstacle_height_
 
double min_obstacle_height_
 
const ros::Duration observation_keep_time_
 
std::list< Observationobservation_list_
 
double obstacle_range_
 
double raytrace_range_
 
std::string sensor_frame_
 
tf::TransformListenertf_
 
double tf_tolerance_
 
std::string topic_name_
 

Detailed Description

Takes in point clouds from sensors, transforms them to the desired frame, and stores them.

Definition at line 61 of file observation_buffer.h.

Constructor & Destructor Documentation

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_nameThe topic of the observations, used as an identifier for error and warning messages
observation_keep_timeDefines the persistence of observations in seconds, 0 means only keep the latest
expected_update_rateHow often this buffer is expected to be updated, 0 means there is no limit
min_obstacle_heightThe minimum height of a hitpoint to be considered legal
max_obstacle_heightThe minimum height of a hitpoint to be considered legal
obstacle_rangeThe range to which the sensor should be trusted for inserting obstacles
raytrace_rangeThe range to which the sensor should be trusted for raytracing to clear out space
tfA reference to a TransformListener
global_frameThe frame to transform PointClouds into
sensor_frameThe frame of the origin of the sensor, can be left blank to be read from the messages
tf_toleranceThe 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 ( )

Destructor... cleans up.

Definition at line 62 of file observation_buffer.cpp.

Member Function Documentation

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
cloudThe 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
cloudThe 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
observationsThe 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

Lock the observation buffer.

Definition at line 126 of file observation_buffer.h.

void costmap_2d::ObservationBuffer::purgeStaleObservations ( )
private

Removes any stale observations from the buffer list.

Definition at line 211 of file observation_buffer.cpp.

void costmap_2d::ObservationBuffer::resetLastUpdated ( )

Reset last updated timestamp.

Definition at line 253 of file observation_buffer.cpp.

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_frameThe 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

Lock the observation buffer.

Definition at line 134 of file observation_buffer.h.

Member Data Documentation

const ros::Duration costmap_2d::ObservationBuffer::expected_update_rate_
private

Definition at line 152 of file observation_buffer.h.

std::string costmap_2d::ObservationBuffer::global_frame_
private

Definition at line 154 of file observation_buffer.h.

ros::Time costmap_2d::ObservationBuffer::last_updated_
private

Definition at line 153 of file observation_buffer.h.

boost::recursive_mutex costmap_2d::ObservationBuffer::lock_
private

A lock for accessing data in callbacks safely.

Definition at line 159 of file observation_buffer.h.

double costmap_2d::ObservationBuffer::max_obstacle_height_
private

Definition at line 158 of file observation_buffer.h.

double costmap_2d::ObservationBuffer::min_obstacle_height_
private

Definition at line 158 of file observation_buffer.h.

const ros::Duration costmap_2d::ObservationBuffer::observation_keep_time_
private

Definition at line 151 of file observation_buffer.h.

std::list<Observation> costmap_2d::ObservationBuffer::observation_list_
private

Definition at line 156 of file observation_buffer.h.

double costmap_2d::ObservationBuffer::obstacle_range_
private

Definition at line 160 of file observation_buffer.h.

double costmap_2d::ObservationBuffer::raytrace_range_
private

Definition at line 160 of file observation_buffer.h.

std::string costmap_2d::ObservationBuffer::sensor_frame_
private

Definition at line 155 of file observation_buffer.h.

tf::TransformListener& costmap_2d::ObservationBuffer::tf_
private

Definition at line 150 of file observation_buffer.h.

double costmap_2d::ObservationBuffer::tf_tolerance_
private

Definition at line 161 of file observation_buffer.h.

std::string costmap_2d::ObservationBuffer::topic_name_
private

Definition at line 157 of file observation_buffer.h.


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 Sun Mar 3 2019 03:44:17