#include <measurement_reading.h>
|
| MeasurementReading () |
|
| MeasurementReading (const MeasurementReading &obs) |
|
| MeasurementReading (geometry_msgs::Point &origin, sensor_msgs::PointCloud2 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 (sensor_msgs::PointCloud2 cloud, double obstacle_range) |
|
Definition at line 57 of file measurement_reading.h.
◆ MeasurementReading() [1/4]
observation::MeasurementReading::MeasurementReading |
( |
| ) |
|
|
inline |
◆ MeasurementReading() [2/4]
observation::MeasurementReading::MeasurementReading |
( |
geometry_msgs::Point & |
origin, |
|
|
sensor_msgs::PointCloud2 |
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 |
|
) |
| |
|
inline |
◆ MeasurementReading() [3/4]
observation::MeasurementReading::MeasurementReading |
( |
sensor_msgs::PointCloud2 |
cloud, |
|
|
double |
obstacle_range |
|
) |
| |
|
inline |
◆ MeasurementReading() [4/4]
◆ _clearing
double observation::MeasurementReading::_clearing |
◆ _cloud
sensor_msgs::PointCloud2::Ptr observation::MeasurementReading::_cloud |
◆ _decay_acceleration
double observation::MeasurementReading::_decay_acceleration |
◆ _horizontal_fov_in_rad
double observation::MeasurementReading::_horizontal_fov_in_rad |
◆ _marking
double observation::MeasurementReading::_marking |
◆ _max_z_in_m
double observation::MeasurementReading::_max_z_in_m |
◆ _min_z_in_m
double observation::MeasurementReading::_min_z_in_m |
◆ _model_type
ModelType observation::MeasurementReading::_model_type |
◆ _obstacle_range_in_m
double observation::MeasurementReading::_obstacle_range_in_m |
◆ _orientation
geometry_msgs::Quaternion observation::MeasurementReading::_orientation |
◆ _origin
◆ _vertical_fov_in_rad
double observation::MeasurementReading::_vertical_fov_in_rad |
◆ _vertical_fov_padding_in_m
double observation::MeasurementReading::_vertical_fov_padding_in_m |
The documentation for this struct was generated from the following file: