Public Member Functions | Private Member Functions | Private Attributes
HeatDetection Class Reference

#include <heat_detection.h>

List of all members.

Public Member Functions

 HeatDetection ()
 ~HeatDetection ()

Private Member Functions

void dynRecParamCallback (HeatDetectionConfig &config, uint32_t level)
void imageCallback (const sensor_msgs::ImageConstPtr &img, const sensor_msgs::CameraInfoConstPtr &info)
void mappingCallback (const thermaleye_msgs::Mapping &mapping)

Private Attributes

dynamic_reconfigure::Server
< HeatDetectionConfig > 
dyn_rec_server_
int image_count_
cv::Mat img_thres_
cv::Mat img_thres_max_
cv::Mat img_thres_min_
thermaleye_msgs::Mapping mapping_
bool mappingDefined_
double maxTempVictim_
double minAreaVictim_
double minDistBetweenBlobs_
double minTempVictim_
std::string perceptClassId_
ros::Publisher pub_
image_transport::CameraPublisher pub_detection_
image_transport::CameraSubscriber sub_
ros::Subscriber sub_mapping_

Detailed Description

Definition at line 21 of file heat_detection.h.


Constructor & Destructor Documentation

Definition at line 4 of file heat_detection.cpp.

Definition at line 23 of file heat_detection.cpp.


Member Function Documentation

void HeatDetection::dynRecParamCallback ( HeatDetectionConfig &  config,
uint32_t  level 
) [private]

Definition at line 162 of file heat_detection.cpp.

void HeatDetection::imageCallback ( const sensor_msgs::ImageConstPtr &  img,
const sensor_msgs::CameraInfoConstPtr &  info 
) [private]

Definition at line 26 of file heat_detection.cpp.

void HeatDetection::mappingCallback ( const thermaleye_msgs::Mapping &  mapping) [private]

Definition at line 156 of file heat_detection.cpp.


Member Data Documentation

dynamic_reconfigure::Server<HeatDetectionConfig> HeatDetection::dyn_rec_server_ [private]

Definition at line 35 of file heat_detection.h.

Definition at line 47 of file heat_detection.h.

cv::Mat HeatDetection::img_thres_ [private]

Definition at line 51 of file heat_detection.h.

cv::Mat HeatDetection::img_thres_max_ [private]

Definition at line 50 of file heat_detection.h.

cv::Mat HeatDetection::img_thres_min_ [private]

Definition at line 49 of file heat_detection.h.

thermaleye_msgs::Mapping HeatDetection::mapping_ [private]

Definition at line 45 of file heat_detection.h.

Definition at line 37 of file heat_detection.h.

Definition at line 40 of file heat_detection.h.

Definition at line 41 of file heat_detection.h.

Definition at line 42 of file heat_detection.h.

Definition at line 39 of file heat_detection.h.

std::string HeatDetection::perceptClassId_ [private]

Definition at line 43 of file heat_detection.h.

Definition at line 30 of file heat_detection.h.

Definition at line 32 of file heat_detection.h.

Definition at line 31 of file heat_detection.h.

Definition at line 33 of file heat_detection.h.


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


hector_heat_detection
Author(s): Konstantin Fuchs
autogenerated on Wed Sep 16 2015 10:20:03