40 #ifndef MEASUREMENT_READING_H_ 41 #define MEASUREMENT_READING_H_ 43 #include <pcl/point_cloud.h> 46 #include <geometry_msgs/Point.h> 47 #include <geometry_msgs/Quaternion.h> 69 double obstacle_range,
double min_z,
double max_z,
double vFOV,
70 double vFOVPadding,
double hFOV,
double decay_acceleration,
bool marking,
117 pcl::PointCloud<pcl::PointXYZ>::Ptr
_cloud;
127 #endif // MEASUREMENT_READING_H_ pcl::PointCloud< pcl::PointXYZ >::Ptr _cloud
geometry_msgs::Point _origin
double _vertical_fov_in_rad
double _obstacle_range_in_m
double _vertical_fov_padding_in_m
sensor_msgs::PointCloud2 PointCloud
MeasurementReading(geometry_msgs::Point &origin, pcl::PointCloud< pcl::PointXYZ > cloud, double obstacle_range, double min_z, double max_z, double vFOV, double vFOVPadding, double hFOV, double decay_acceleration, bool marking, bool clearing, ModelType model_type)
MeasurementReading(pcl::PointCloud< pcl::PointXYZ > cld, double obstacle_range)
double _decay_acceleration
double _horizontal_fov_in_rad
MeasurementReading(const MeasurementReading &obs)
geometry_msgs::Quaternion _orientation