#include "ros/ros.h"
#include <image_transport/image_transport.h>
#include <sensor_msgs/TimeReference.h>
#include "std_msgs/Float32.h"
#include "std_srvs/Empty.h"
#include "optris_drivers/AutoFlag.h"
#include "optris_drivers/SwitchTemperatureRange.h"
#include <optris_drivers/Temperature.h>
#include "libirimager/IRImager.h"
#include "libirimager/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) |
bool | onSwitchTemperatureRange (optris_drivers::SwitchTemperatureRange::Request &req, optris_drivers::SwitchTemperatureRange::Response &res) |
void | onThermalFrame (unsigned short *image, unsigned int w, unsigned int h, long long timestamp, void *arg) |
void | onVisibleFrame (unsigned char *image, unsigned int w, unsigned int h, long long timestamp, void *arg) |
Variables | |
optris::IRImager * | _imager |
unsigned int | _img_cnt = 0 |
optris_drivers::Temperature | _internal_temperature |
sensor_msgs::TimeReference | _optris_timer |
ros::Publisher | _temp_pub |
sensor_msgs::Image | _thermal_image |
image_transport::Publisher * | _thermal_pub = NULL |
ros::Publisher | _timer_pub |
sensor_msgs::Image | _visible_image |
image_transport::Publisher * | _visible_pub = NULL |
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 158 of file optris_imager_node.cpp.
bool onAutoFlag | ( | optris_drivers::AutoFlag::Request & | req, |
optris_drivers::AutoFlag::Response & | res | ||
) |
Definition at line 118 of file optris_imager_node.cpp.
bool onForceFlag | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | res | ||
) |
Definition at line 125 of file optris_imager_node.cpp.
bool onSwitchTemperatureRange | ( | optris_drivers::SwitchTemperatureRange::Request & | req, |
optris_drivers::SwitchTemperatureRange::Response & | res | ||
) |
Definition at line 131 of file optris_imager_node.cpp.
void onThermalFrame | ( | unsigned short * | image, |
unsigned int | w, | ||
unsigned int | h, | ||
long long | timestamp, | ||
void * | arg | ||
) |
Callback method from image processing library (called at configured frame rate in 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 |
[in] | timestamp | the frame's timestamp |
[in] | arg | user argument passed to process method |
Definition at line 76 of file optris_imager_node.cpp.
void onVisibleFrame | ( | unsigned char * | image, |
unsigned int | w, | ||
unsigned int | h, | ||
long long | timestamp, | ||
void * | arg | ||
) |
Callback method from image processing library (called at configured frame rate in xml file)
[in] | image | RGB image, if BISPECTRAL technology is available |
[in] | w | image width |
[in] | h | image height |
[in] | timestamp | the frame's timestamp |
[in] | arg | user argument passed to process method |
Definition at line 107 of file optris_imager_node.cpp.
optris::IRImager* _imager |
Definition at line 66 of file optris_imager_node.cpp.
unsigned int _img_cnt = 0 |
Definition at line 65 of file optris_imager_node.cpp.
optris_drivers::Temperature _internal_temperature |
Definition at line 57 of file optris_imager_node.cpp.
sensor_msgs::TimeReference _optris_timer |
Definition at line 56 of file optris_imager_node.cpp.
Definition at line 63 of file optris_imager_node.cpp.
sensor_msgs::Image _thermal_image |
Definition at line 54 of file optris_imager_node.cpp.
Definition at line 59 of file optris_imager_node.cpp.
Definition at line 62 of file optris_imager_node.cpp.
sensor_msgs::Image _visible_image |
Definition at line 55 of file optris_imager_node.cpp.
Definition at line 60 of file optris_imager_node.cpp.