#include <laser_height.h>
Definition at line 54 of file laser_height.h.
mav::LaserHeightEstimation::LaserHeightEstimation | ( | ros::NodeHandle | nh, |
ros::NodeHandle | nh_private | ||
) |
Definition at line 42 of file laser_height.cpp.
mav::LaserHeightEstimation::~LaserHeightEstimation | ( | ) | [virtual] |
Definition at line 83 of file laser_height.cpp.
void mav::LaserHeightEstimation::getStats | ( | const std::vector< double > | values, |
double & | ave, | ||
double & | stdev | ||
) | [private] |
Definition at line 256 of file laser_height.cpp.
void mav::LaserHeightEstimation::histogramSegmentation | ( | const std::vector< double > & | input, |
std::vector< double > & | output | ||
) | [private] |
Definition at line 271 of file laser_height.cpp.
void mav::LaserHeightEstimation::imuCallback | ( | const sensor_msgs::ImuPtr & | imu_msg | ) | [private] |
Definition at line 87 of file laser_height.cpp.
void mav::LaserHeightEstimation::scanCallback | ( | const sensor_msgs::LaserScanPtr & | scan_msg | ) | [private] |
Definition at line 98 of file laser_height.cpp.
bool mav::LaserHeightEstimation::setBaseToLaserTf | ( | const sensor_msgs::LaserScanPtr & | scan_msg | ) | [private] |
Definition at line 216 of file laser_height.cpp.
std::string mav::LaserHeightEstimation::base_frame_ [private] |
Definition at line 93 of file laser_height.h.
Definition at line 83 of file laser_height.h.
Definition at line 82 of file laser_height.h.
double mav::LaserHeightEstimation::bin_size_ [private] |
Definition at line 102 of file laser_height.h.
bool mav::LaserHeightEstimation::first_time_ [private] |
Definition at line 79 of file laser_height.h.
Definition at line 69 of file laser_height.h.
Definition at line 70 of file laser_height.h.
Definition at line 71 of file laser_height.h.
Definition at line 67 of file laser_height.h.
std::string mav::LaserHeightEstimation::imu_topic_ [private] |
Definition at line 95 of file laser_height.h.
bool mav::LaserHeightEstimation::initialized_ [private] |
Definition at line 78 of file laser_height.h.
Definition at line 88 of file laser_height.h.
sensor_msgs::Imu mav::LaserHeightEstimation::latest_imu_msg_ [private] |
Definition at line 86 of file laser_height.h.
double mav::LaserHeightEstimation::max_height_jump_ [private] |
Definition at line 99 of file laser_height.h.
double mav::LaserHeightEstimation::max_stdev_ [private] |
Definition at line 98 of file laser_height.h.
int mav::LaserHeightEstimation::min_values_ [private] |
Definition at line 97 of file laser_height.h.
boost::mutex mav::LaserHeightEstimation::mutex_ [private] |
Definition at line 76 of file laser_height.h.
Definition at line 65 of file laser_height.h.
Definition at line 66 of file laser_height.h.
double mav::LaserHeightEstimation::prev_height_ [private] |
Definition at line 80 of file laser_height.h.
Definition at line 68 of file laser_height.h.
std::string mav::LaserHeightEstimation::scan_topic_ [private] |
Definition at line 96 of file laser_height.h.
std::string mav::LaserHeightEstimation::stabilized_frame_ [private] |
Definition at line 94 of file laser_height.h.
Definition at line 72 of file laser_height.h.
bool mav::LaserHeightEstimation::use_imu_ [private] |
Definition at line 100 of file laser_height.h.
bool mav::LaserHeightEstimation::use_segmentation_ [private] |
Definition at line 101 of file laser_height.h.
std::string mav::LaserHeightEstimation::world_frame_ [private] |
Definition at line 92 of file laser_height.h.
Definition at line 84 of file laser_height.h.