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. | |
| 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_ |
Stores an observation in terms of a point cloud and the origin of the source.
Definition at line 47 of file observation.h.
| costmap_2d::Observation::Observation | ( | ) | [inline] |
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.
| 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 70 of file observation.h.
| costmap_2d::Observation::Observation | ( | const Observation & | obs | ) | [inline] |
Copy constructor.
| obs | The 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.
| 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 92 of file observation.h.
| pcl::PointCloud<pcl::PointXYZ>* costmap_2d::Observation::cloud_ |
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.