Distance sensor mapping storage item. More...
Public Types | |
typedef boost::shared_ptr< DistanceSensorItem > | Ptr |
Public Member Functions | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | DistanceSensorItem () |
void | range_cb (const sensor_msgs::Range::ConstPtr &msg) |
Static Public Member Functions | |
static Ptr | create_item (DistanceSensorPlugin *owner, std::string topic_name) |
Public Attributes | |
int | covariance |
in centimeters, current specification More... | |
double | field_of_view |
FOV of the sensor. More... | |
std::string | frame_id |
frame id for send More... | |
double | horizontal_fov_ratio |
horizontal fov ratio for ROS messages More... | |
bool | is_subscriber |
this item is a subscriber, else is a publisher More... | |
int | orientation |
check orientation of sensor if != -1 More... | |
DistanceSensorPlugin * | owner |
Eigen::Vector3d | position |
sensor position More... | |
ros::Publisher | pub |
Eigen::Quaternionf | quaternion |
sensor orientation in vehicle body frame for MAV_SENSOR_ROTATION_CUSTOM More... | |
bool | send_tf |
defines if a transform is sent or not More... | |
uint8_t | sensor_id |
id of the sensor More... | |
ros::Subscriber | sub |
std::string | topic_name |
double | vertical_fov_ratio |
vertical fov ratio for ROS messages More... | |
Private Member Functions | |
float | calculate_variance (float range) |
Private Attributes | |
std::vector< float > | data |
array allocation for measurements More... | |
size_t | data_index |
array index More... | |
Static Private Attributes | |
static constexpr size_t | ACC_SIZE = 50 |
Distance sensor mapping storage item.
Definition at line 31 of file distance_sensor.cpp.