#include <heat_detection.h>
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_ |
Definition at line 21 of file heat_detection.h.
Definition at line 4 of file heat_detection.cpp.
Definition at line 23 of file heat_detection.cpp.
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.
dynamic_reconfigure::Server<HeatDetectionConfig> HeatDetection::dyn_rec_server_ [private] |
Definition at line 35 of file heat_detection.h.
int HeatDetection::image_count_ [private] |
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.
bool HeatDetection::mappingDefined_ [private] |
Definition at line 37 of file heat_detection.h.
double HeatDetection::maxTempVictim_ [private] |
Definition at line 40 of file heat_detection.h.
double HeatDetection::minAreaVictim_ [private] |
Definition at line 41 of file heat_detection.h.
double HeatDetection::minDistBetweenBlobs_ [private] |
Definition at line 42 of file heat_detection.h.
double HeatDetection::minTempVictim_ [private] |
Definition at line 39 of file heat_detection.h.
std::string HeatDetection::perceptClassId_ [private] |
Definition at line 43 of file heat_detection.h.
ros::Publisher HeatDetection::pub_ [private] |
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.
ros::Subscriber HeatDetection::sub_mapping_ [private] |
Definition at line 33 of file heat_detection.h.