mav::LaserHeightEstimation Class Reference

#include <laser_height_estimation.h>

List of all members.

Public Member Functions

 LaserHeightEstimation (ros::NodeHandle nh, ros::NodeHandle nh_private)
virtual ~LaserHeightEstimation ()

Private Member Functions

void getStats (const std::vector< double > values, double &ave, double &stdev)
void imuCallback (const sensor_msgs::ImuPtr &imu_msg)
void scanCallback (const sensor_msgs::LaserScanPtr &scan_msg)
bool setBaseToLaserTf (const sensor_msgs::LaserScanPtr &scan_msg)

Private Attributes

std::string base_frame_
btTransform base_to_footprint_
btTransform base_to_laser_
double floor_height_
std::string footprint_frame_
ros::Publisher height_to_base_publisher_
ros::Publisher height_to_footprint_publisher_
ros::Subscriber imu_subscriber_
bool initialized_
ros::Time last_update_time_
sensor_msgs::Imu latest_imu_msg_
double max_height_jump_
double max_stdev_
int min_values_
ros::NodeHandle nh_
ros::NodeHandle nh_private_
double prev_height_
ros::Subscriber scan_subscriber_
tf::TransformListener tf_listener_
bool use_imu_
std::string world_frame_
btTransform world_to_base_

Detailed Description

Definition at line 55 of file laser_height_estimation.h.


Constructor & Destructor Documentation

mav::LaserHeightEstimation::LaserHeightEstimation ( ros::NodeHandle  nh,
ros::NodeHandle  nh_private 
)

Definition at line 42 of file laser_height_estimation.cpp.

mav::LaserHeightEstimation::~LaserHeightEstimation (  )  [virtual]

Definition at line 89 of file laser_height_estimation.cpp.


Member Function Documentation

void mav::LaserHeightEstimation::getStats ( const std::vector< double >  values,
double &  ave,
double &  stdev 
) [private]

Definition at line 281 of file laser_height_estimation.cpp.

void mav::LaserHeightEstimation::imuCallback ( const sensor_msgs::ImuPtr &  imu_msg  )  [private]

Definition at line 94 of file laser_height_estimation.cpp.

void mav::LaserHeightEstimation::scanCallback ( const sensor_msgs::LaserScanPtr &  scan_msg  )  [private]

Definition at line 110 of file laser_height_estimation.cpp.

bool mav::LaserHeightEstimation::setBaseToLaserTf ( const sensor_msgs::LaserScanPtr &  scan_msg  )  [private]

Definition at line 234 of file laser_height_estimation.cpp.


Member Data Documentation

Definition at line 86 of file laser_height_estimation.h.

Definition at line 76 of file laser_height_estimation.h.

Definition at line 75 of file laser_height_estimation.h.

Definition at line 72 of file laser_height_estimation.h.

Definition at line 87 of file laser_height_estimation.h.

Definition at line 65 of file laser_height_estimation.h.

Definition at line 66 of file laser_height_estimation.h.

Definition at line 63 of file laser_height_estimation.h.

Definition at line 71 of file laser_height_estimation.h.

Definition at line 81 of file laser_height_estimation.h.

sensor_msgs::Imu mav::LaserHeightEstimation::latest_imu_msg_ [private]

Definition at line 79 of file laser_height_estimation.h.

Definition at line 90 of file laser_height_estimation.h.

Definition at line 89 of file laser_height_estimation.h.

Definition at line 88 of file laser_height_estimation.h.

ros::NodeHandle mav::LaserHeightEstimation::nh_ [private]

Definition at line 61 of file laser_height_estimation.h.

ros::NodeHandle mav::LaserHeightEstimation::nh_private_ [private]

Definition at line 62 of file laser_height_estimation.h.

Definition at line 73 of file laser_height_estimation.h.

Definition at line 64 of file laser_height_estimation.h.

tf::TransformListener mav::LaserHeightEstimation::tf_listener_ [private]

Definition at line 67 of file laser_height_estimation.h.

Definition at line 91 of file laser_height_estimation.h.

Definition at line 85 of file laser_height_estimation.h.

Definition at line 77 of file laser_height_estimation.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs


laser_height_estimation
Author(s): Ivan Dryanovski
autogenerated on Fri Jan 11 10:00:30 2013