Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include "ros/ros.h"
00040 #include <image_transport/image_transport.h>
00041 #include <dynamic_reconfigure/server.h>
00042
00043 #include <optris_drivers/ThresholdConfig.h>
00044
00045 #include "libirimager/ImageBuilder.h"
00046
00047 image_transport::Publisher* _pubThermal;
00048
00049 double _threshold = 40.0;
00050 bool _invert = false;
00051
00052
00057 void onThermalDataReceive(const sensor_msgs::ImageConstPtr& image)
00058 {
00059 static unsigned int frame = 0;
00060
00061 unsigned short* data = (unsigned short*)&image->data[0];
00062
00063 sensor_msgs::Image img;
00064 img.header.frame_id = "thermal_image_view";
00065 img.height = image->height;
00066 img.width = image->width;
00067 img.encoding = "mono8";
00068 img.step = image->width;
00069 img.data.resize(img.height*img.step);
00070 img.header.seq = ++frame;
00071 img.header.stamp = ros::Time::now();
00072
00073
00074 for(unsigned int i=0; i<image->width*image->height; i++)
00075 {
00076 const double temp = (float(data[i]) -1000.0f)/10.0f;
00077
00078 if(!_invert) {
00079 if(temp > _threshold) img.data[i] = 0xff;
00080 else img.data[i] = 0x00;
00081 }
00082 else {
00083 if(temp > _threshold) img.data[i] = 0x00;
00084 else img.data[i] = 0xff;
00085 }
00086
00087 }
00088
00089 _pubThermal->publish(img);
00090 }
00091
00092
00098 void callback(optris_drivers::ThresholdConfig &config, uint32_t level)
00099 {
00100 _threshold = config.threshold;
00101 _invert = config.invert;
00102 }
00103
00104
00105
00115 int main (int argc, char* argv[])
00116 {
00117 ros::init (argc, argv, "optris_binary_image_node");
00118
00119
00120 dynamic_reconfigure::Server<optris_drivers::ThresholdConfig> server;
00121 dynamic_reconfigure::Server<optris_drivers::ThresholdConfig>::CallbackType f;
00122
00123 f = boost::bind(&callback, _1, _2);
00124 server.setCallback(f);
00125
00126
00127 ros::NodeHandle n_("~");
00128
00129
00130 _threshold = 40.0;
00131 n_.getParam("threshold", _threshold);
00132 _invert = false;
00133 n_.getParam("invert", _invert);
00134
00135
00136
00137 ros::NodeHandle n;
00138 image_transport::ImageTransport it(n);
00139 image_transport::Subscriber subThermal = it.subscribe("thermal_image", 1, onThermalDataReceive);
00140 image_transport::Publisher pubt = it.advertise("thermal_binary", 1);
00141 _pubThermal = &pubt;
00142
00143
00144 ros::Rate loop_rate(30);
00145 while (ros::ok())
00146 {
00147 ros::spinOnce();
00148 loop_rate.sleep();
00149 }
00150 }
optris_drivers
Author(s): Stefan May (Nuremberg Institute of Technology Georg Simon Ohm - www.th-nuernberg.de), 64-Bit platform supported by Fraunhofer IPA (www.ipa.fraunhofer.de), Support for ROS hydro migration by Christopher-Eyk Hrabia (DAI-Labor, Technische Universität Berlin)
autogenerated on Thu Jun 6 2019 22:02:23