Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
mavros::extra_plugins::DistanceSensorItem Class Reference

Distance sensor mapping storage item. More...

Public Types

typedef boost::shared_ptr< DistanceSensorItemPtr
 

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...
 
bool is_subscriber
 this item is a subscriber, else is a publisher More...
 
int orientation
 check orientation of sensor if != -1 More...
 
DistanceSensorPluginowner
 
Eigen::Vector3d position
 sensor position More...
 
ros::Publisher pub
 
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
 

Private Member Functions

float calculate_variance (float range)
 

Private Attributes

std::vector< floatdata
 array allocation for measurements More...
 
size_t data_index
 array index More...
 

Static Private Attributes

static constexpr size_t ACC_SIZE = 50
 

Detailed Description

Distance sensor mapping storage item.

Definition at line 31 of file distance_sensor.cpp.


The documentation for this class was generated from the following file:


mavros_extras
Author(s): Vladimir Ermakov
autogenerated on Mon Jul 8 2019 03:20:18