Distance sensor mapping storage item. More...
Public Types | |
| typedef boost::shared_ptr < DistanceSensorItem > | Ptr |
Public Member Functions | |
| 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 | |
| double | field_of_view |
| FOV of the sensor. | |
| std::string | frame_id |
| frame id for send | |
| bool | is_subscriber |
| this item is a subscriber, else is a publisher | |
| int | orientation |
| check orientation of sensor if != -1 | |
| DistanceSensorPlugin * | owner |
| Eigen::Vector3d | position |
| sensor position | |
| ros::Publisher | pub |
| bool | send_tf |
| defines if a transform is sent or not | |
| uint8_t | sensor_id |
| id of the sensor | |
| ros::Subscriber | sub |
| std::string | topic_name |
Private Member Functions | |
| float | calculate_variance (float range) |
Private Attributes | |
| std::vector< float > | data |
| array allocation for measurements | |
| size_t | data_index |
| array index | |
Distance sensor mapping storage item.
Definition at line 30 of file distance_sensor.cpp.