#include "ros/ros.h"#include <image_transport/image_transport.h>#include "std_msgs/Float32.h"#include "std_srvs/Empty.h"#include "optris_drivers/AutoFlag.h"#include "PIImager.h"#include "ImageBuilder.h"#include <sys/stat.h>
Go to the source code of this file.
Functions | |
| int | main (int argc, char **argv) | 
| bool | onAutoFlag (optris_drivers::AutoFlag::Request &req, optris_drivers::AutoFlag::Response &res) | 
| bool | onForceFlag (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) | 
| void | onThermalFrame (unsigned short *image, unsigned int w, unsigned int h) | 
| void | onVisibleFrame (unsigned char *image, unsigned int w, unsigned int h) | 
Variables | |
| ros::Publisher | _box_pub | 
| std_msgs::Float32 | _box_temperature | 
| ros::Publisher | _chip_pub | 
| std_msgs::Float32 | _chip_temperature | 
| ros::Publisher | _flag_pub | 
| std_msgs::Float32 | _flag_temperature | 
| optris::PIImager * | _imager | 
| unsigned int | _img_cnt = 0 | 
| sensor_msgs::Image | _thermal_image | 
| image_transport::Publisher * | _thermal_pub | 
| sensor_msgs::Image | _visible_image | 
| image_transport::Publisher * | _visible_pub | 
| int main | ( | int | argc, | 
| char ** | argv | ||
| ) | 
Definition at line 108 of file optris_imager_node.cpp.
| bool onAutoFlag | ( | optris_drivers::AutoFlag::Request & | req, | 
| optris_drivers::AutoFlag::Response & | res | ||
| ) | 
Definition at line 96 of file optris_imager_node.cpp.
| bool onForceFlag | ( | std_srvs::Empty::Request & | req, | 
| std_srvs::Empty::Response & | res | ||
| ) | 
Definition at line 102 of file optris_imager_node.cpp.
| void onThermalFrame | ( | unsigned short * | image, | 
| unsigned int | w, | ||
| unsigned int | h | ||
| ) | 
Callback method from image processing library (called with configured frame rate from xml file)
| [in] | image | thermal image in unsigned short format, i.e., float temperature = ((float)image[i] -1000.f)/10.f) | 
| [in] | w | image width | 
| [in] | h | image height | 
Definition at line 71 of file optris_imager_node.cpp.
| void onVisibleFrame | ( | unsigned char * | image, | 
| unsigned int | w, | ||
| unsigned int | h | ||
| ) | 
Definition at line 87 of file optris_imager_node.cpp.
| ros::Publisher _box_pub | 
Definition at line 59 of file optris_imager_node.cpp.
| std_msgs::Float32 _box_temperature | 
Definition at line 53 of file optris_imager_node.cpp.
| ros::Publisher _chip_pub | 
Definition at line 60 of file optris_imager_node.cpp.
| std_msgs::Float32 _chip_temperature | 
Definition at line 54 of file optris_imager_node.cpp.
| ros::Publisher _flag_pub | 
Definition at line 58 of file optris_imager_node.cpp.
| std_msgs::Float32 _flag_temperature | 
Definition at line 52 of file optris_imager_node.cpp.
Definition at line 63 of file optris_imager_node.cpp.
| unsigned int _img_cnt = 0 | 
Definition at line 62 of file optris_imager_node.cpp.
| sensor_msgs::Image _thermal_image | 
Definition at line 50 of file optris_imager_node.cpp.
| image_transport::Publisher* _thermal_pub | 
Definition at line 56 of file optris_imager_node.cpp.
| sensor_msgs::Image _visible_image | 
Definition at line 51 of file optris_imager_node.cpp.
| image_transport::Publisher* _visible_pub | 
Definition at line 57 of file optris_imager_node.cpp.