$search

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 (pcl::PointCloud< pcl::PointXYZ > cloud, double obstacle_range)
 Creates an observation from a point cloud.
 Observation (const Observation &obs)
 Copy constructor.
 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 ()
 Creates an empty 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

costmap_2d::Observation::Observation (  )  [inline]

Creates an empty observation.

Definition at line 52 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:
origin The origin point of the observation
cloud The point cloud of the observation
obstacle_range The range out to which an observation should be able to insert obstacles
raytrace_range The range out to which an observation should be able to clear via raytracing

Definition at line 60 of file observation.h.

costmap_2d::Observation::Observation ( const Observation obs  )  [inline]

Copy constructor.

Parameters:
obs The observation to copy

Definition at line 67 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:
cloud The point cloud of the observation
obstacle_range The range out to which an observation should be able to insert obstacles

Definition at line 74 of file observation.h.


Member Data Documentation

pcl::PointCloud<pcl::PointXYZ> costmap_2d::Observation::cloud_

Definition at line 77 of file observation.h.

Definition at line 78 of file observation.h.

Definition at line 76 of file observation.h.

Definition at line 78 of file observation.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


costmap_2d
Author(s): Eitan Marder-Eppstein
autogenerated on Fri Mar 1 16:10:00 2013