Public Member Functions | Public Attributes
costmap_2d::Observation Class Reference

Stores an observation in terms of a point cloud and the origin of the source. More...

#include <observation.h>

List of all members.

Public Member Functions

 Observation ()
 Creates an empty observation.
 Observation (geometry_msgs::Point &origin, pcl::PointCloud< pcl::PointXYZ > cloud, double obstacle_range, double raytrace_range)
 Creates an observation from an origin point and a point cloud.
 Observation (const Observation &obs)
 Copy constructor.
 Observation (pcl::PointCloud< pcl::PointXYZ > cloud, double obstacle_range)
 Creates an observation from a point cloud.
virtual ~Observation ()

Public Attributes

pcl::PointCloud< pcl::PointXYZ > * cloud_
double obstacle_range_
geometry_msgs::Point origin_
double raytrace_range_

Detailed Description

Stores an observation in terms of a point cloud and the origin of the source.

Note:
Tried to make members and constructor arguments const but the compiler would not accept the default assignment operator for vector insertion!

Definition at line 47 of file observation.h.


Constructor & Destructor Documentation

Creates an empty observation.

Definition at line 53 of file observation.h.

virtual costmap_2d::Observation::~Observation ( ) [inline, virtual]

Definition at line 58 of file observation.h.

costmap_2d::Observation::Observation ( geometry_msgs::Point origin,
pcl::PointCloud< pcl::PointXYZ >  cloud,
double  obstacle_range,
double  raytrace_range 
) [inline]

Creates an observation from an origin point and a point cloud.

Parameters:
originThe origin point of the observation
cloudThe point cloud of the observation
obstacle_rangeThe range out to which an observation should be able to insert obstacles
raytrace_rangeThe range out to which an observation should be able to clear via raytracing

Definition at line 70 of file observation.h.

Copy constructor.

Parameters:
obsThe observation to copy

Definition at line 81 of file observation.h.

costmap_2d::Observation::Observation ( pcl::PointCloud< pcl::PointXYZ >  cloud,
double  obstacle_range 
) [inline]

Creates an observation from a point cloud.

Parameters:
cloudThe point cloud of the observation
obstacle_rangeThe range out to which an observation should be able to insert obstacles

Definition at line 92 of file observation.h.


Member Data Documentation

Definition at line 98 of file observation.h.

Definition at line 99 of file observation.h.

Definition at line 97 of file observation.h.

Definition at line 99 of file observation.h.


The documentation for this class was generated from the following file:


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Wed Aug 2 2017 03:12:22