Stores an observation in terms of a point cloud and the origin of the source. More...
#include <observation.h>
Public Member Functions | |
| Observation () | |
| Creates an empty observation. More... | |
| Observation (geometry_msgs::Point &origin, const sensor_msgs::PointCloud2 &cloud, double obstacle_range, double raytrace_range) | |
| Creates an observation from an origin point and a point cloud. More... | |
| Observation (const Observation &obs) | |
| Copy constructor. More... | |
| Observation (const sensor_msgs::PointCloud2 &cloud, double obstacle_range) | |
| Creates an observation from a point cloud. More... | |
| virtual | ~Observation () |
Public Attributes | |
| sensor_msgs::PointCloud2 * | cloud_ |
| double | obstacle_range_ |
| geometry_msgs::Point | origin_ |
| double | raytrace_range_ |
Stores an observation in terms of a point cloud and the origin of the source.
Definition at line 46 of file observation.h.
|
inline |
Creates an empty observation.
Definition at line 52 of file observation.h.
|
inlinevirtual |
Definition at line 57 of file observation.h.
|
inline |
Creates an observation from an origin point and a point cloud.
| 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 69 of file observation.h.
|
inline |
Copy constructor.
| obs | The observation to copy |
Definition at line 80 of file observation.h.
|
inline |
Creates an observation from a point cloud.
| 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 91 of file observation.h.
| sensor_msgs::PointCloud2* costmap_2d::Observation::cloud_ |
Definition at line 97 of file observation.h.
| double costmap_2d::Observation::obstacle_range_ |
Definition at line 98 of file observation.h.
| geometry_msgs::Point costmap_2d::Observation::origin_ |
Definition at line 96 of file observation.h.
| double costmap_2d::Observation::raytrace_range_ |
Definition at line 98 of file observation.h.