optris_colorconvert_node.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012-2016
5  * Technische Hochschule Nürnberg Georg Simon Ohm
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Nuremberg Institute of Technology
19  * Georg Simon Ohm nor the authors names may be used to endorse
20  * or promote products derived from this software without specific
21  * prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Stefan May
37  *********************************************************************/
38 
39 #include "ros/ros.h"
41 
42 #include "libirimager/ImageBuilder.h"
43 
45 #include <sensor_msgs/CameraInfo.h>
46 
47 #include <optris_drivers/Palette.h>
48 
49 unsigned char* _bufferThermal = NULL;
50 unsigned char* _bufferVisible = NULL;
53 unsigned int _frame = 0;
54 
55 evo::ImageBuilder _iBuilder;
56 
57 sensor_msgs::CameraInfo _camera_info;
61 
62 void onThermalDataReceive(const sensor_msgs::ImageConstPtr& image)
63 {
64  // check for any subscribers to save computation time
65  if((_pubThermal->getNumSubscribers() == 0) && (_camera_info_pub->getNumSubscribers() == 0))
66  return;
67 
68  unsigned short* data = (unsigned short*)&image->data[0];
69  _iBuilder.setData(image->width, image->height, data);
70 
71  if(_bufferThermal==NULL)
72  _bufferThermal = new unsigned char[image->width * image->height * 3];
73 
74  _iBuilder.convertTemperatureToPaletteImage(_bufferThermal, true);
75 
76  sensor_msgs::Image img;
77  img.header.frame_id = "thermal_image_view";
78  img.height = image->height;
79  img.width = image->width;
80  img.encoding = "rgb8";
81  img.step = image->width*3;
82  img.header.seq = ++_frame;
83  img.header.stamp = ros::Time::now();
84 
85  // copy the image buffer
86  img.data.resize(img.height*img.step);
87  memcpy(&img.data[0], &_bufferThermal[0], img.height * img.step * sizeof(*_bufferThermal));
88 
89  _camera_info = _camera_info_manager->getCameraInfo();
90  _camera_info.header = img.header;
91  _camera_info_pub->publish(img, _camera_info);
92 
93  _pubThermal->publish(img);
94 }
95 
96 void onVisibleDataReceive(const sensor_msgs::ImageConstPtr& image)
97 {
98  // check for any subscribers to save computation time
99  if(_pubVisible->getNumSubscribers() == 0)
100  return;
101 
102  if(_bufferVisible==NULL)
103  _bufferVisible = new unsigned char[image->width * image->height * 3];
104 
105  const unsigned char* data = &image->data[0];
106  _iBuilder.yuv422torgb24(data, _bufferVisible, image->width, image->height);
107 
108  sensor_msgs::Image img;
109  img.header.frame_id = "visible_image_view";
110  img.height = image->height;
111  img.width = image->width;
112  img.encoding = "rgb8";
113  img.step = image->width*3;
114  img.data.resize(img.height*img.step);
115 
116  img.header.seq = _frame;
117  img.header.stamp = ros::Time::now();
118 
119  for(unsigned int i=0; i<image->width*image->height*3; i++) {
120  img.data[i] = _bufferVisible[i];
121  }
122 
123  _pubVisible->publish(img);
124 }
125 
126 bool onPalette(optris_drivers::Palette::Request &req, optris_drivers::Palette::Response &res)
127 {
128  res.success = false;
129 
130  if(req.palette > 0 && req.palette < 12)
131  {
132  _iBuilder.setPalette((evo::EnumOptrisColoringPalette)req.palette);
133  res.success = true;
134  }
135 
136  if(req.paletteScaling >=1 && req.paletteScaling <= 4)
137  {
138  _iBuilder.setPaletteScalingMethod((evo::EnumOptrisPaletteScalingMethod) req.paletteScaling);
139  res.success = true;
140  }
141 
142  if(_iBuilder.getPaletteScalingMethod() == evo::eManual && req.temperatureMin < req.temperatureMax)
143  {
144  _iBuilder.setManualTemperatureRange(req.temperatureMin, req.temperatureMax);
145  res.success = true;
146  }
147 
148  return true;
149 }
150 
151 int main (int argc, char* argv[])
152 {
153  ros::init (argc, argv, "optris_colorconvert_node");
154 
155  // private node handle to support command line parameters for rosrun
156  ros::NodeHandle n_("~");
157 
158  int palette = 6;
159  n_.getParam("palette", palette);
160 
161  evo::EnumOptrisPaletteScalingMethod scalingMethod = evo::eMinMax;
162  int sm;
163  n_.getParam("paletteScaling", sm);
164  if(sm>=1 && sm <=4) scalingMethod = (evo::EnumOptrisPaletteScalingMethod) sm;
165 
166  _iBuilder.setPaletteScalingMethod(scalingMethod);
167  _iBuilder.setPalette((evo::EnumOptrisColoringPalette)palette);
168 
169  double tMin = 20.;
170  double tMax = 40.;
171  double looprate = 30.;
172 
173  n_.getParam("temperatureMin", tMin);
174  n_.getParam("temperatureMax", tMax);
175  n_.getParam("looprate", looprate);
176 
177  _iBuilder.setManualTemperatureRange((float)tMin, (float)tMax);
178 
179  ros::NodeHandle n;
181  image_transport::Subscriber subThermal = it.subscribe("thermal_image", 1, onThermalDataReceive);
182  image_transport::Subscriber subVisible = it.subscribe("visible_image", 1, onVisibleDataReceive);
183 
184  image_transport::Publisher pubt = it.advertise("thermal_image_view", 1);
185  image_transport::Publisher pubv = it.advertise("visible_image_view", 1);
186 
187  _pubThermal = &pubt;
188  _pubVisible = &pubv;
189 
190  _sPalette = n.advertiseService("palette", &onPalette);
191 
192  std::string camera_name;
193  std::string camera_info_url;
194  n_.getParam("camera_name", camera_name);
195  n_.getParam("camera_info_url", camera_info_url);
196 
197  // initialize CameraInfoManager, providing set_camera_info service for geometric calibration
198  // see http://wiki.ros.org/camera_info_manager
200  _camera_info_manager = &cinfo_manager;
201 
202  if (!_camera_info_manager->setCameraName(camera_name))
203  {
204  // GUID is 16 hex digits, which should be valid.
205  // If not, use it for log messages anyway.
206  ROS_WARN_STREAM("[" << camera_name << "] name not valid" << " for camera_info_manger");
207  }
208 
209  if (_camera_info_manager->validateURL(camera_info_url))
210  {
211  if ( !_camera_info_manager->loadCameraInfo(camera_info_url) )
212  {
213  ROS_WARN( "camera_info_url does not contain calibration data." );
214  }
215  else if ( !_camera_info_manager->isCalibrated() )
216  {
217  ROS_WARN( "Camera is not calibrated. Using default values." );
218  }
219  }
220  else
221  {
222  ROS_ERROR_STREAM_ONCE( "Calibration URL syntax is not supported by CameraInfoManager." );
223  }
224 
225  // Advertise a synchronized camera raw image + info topic pair with subscriber status callbacks.
226  image_transport::CameraPublisher cinfo_pub = it.advertiseCamera("image_raw", 1);
227  _camera_info_pub = &cinfo_pub;
228 
229  // set to png compression
230  std::string key;
231  if(ros::param::search("thermal_image/compressed/format", key))
232  {
233  ros::param::set(key, "png");
234  }
235  if(ros::param::search("thermal_image/compressed/png_level", key))
236  {
237  ros::param::set(key, 9);
238  }
239 
240  ros::spin();
241 
242  if(_bufferThermal) delete [] _bufferThermal;
243  if(_bufferVisible) delete [] _bufferVisible;
244 }
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
sensor_msgs::CameraInfo getCameraInfo(void)
image_transport::Publisher * _pubThermal
unsigned char * _bufferThermal
bool loadCameraInfo(const std::string &url)
uint32_t getNumSubscribers() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
#define ROS_WARN(...)
uint32_t getNumSubscribers() const
camera_info_manager::CameraInfoManager * _camera_info_manager
bool validateURL(const std::string &url)
ROSCPP_DECL void spin(Spinner &spinner)
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
unsigned char * _bufferVisible
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::CameraPublisher * _camera_info_pub
evo::ImageBuilder _iBuilder
bool onPalette(optris_drivers::Palette::Request &req, optris_drivers::Palette::Response &res)
void publish(const sensor_msgs::Image &message) const
image_transport::Publisher * _pubVisible
int main(int argc, char *argv[])
sensor_msgs::CameraInfo _camera_info
#define ROS_WARN_STREAM(args)
ros::ServiceServer _sPalette
unsigned int _frame
bool getParam(const std::string &key, std::string &s) const
static Time now()
#define ROS_ERROR_STREAM_ONCE(args)
void onVisibleDataReceive(const sensor_msgs::ImageConstPtr &image)
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
void onThermalDataReceive(const sensor_msgs::ImageConstPtr &image)
bool setCameraName(const std::string &cname)


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 Mon Jun 10 2019 14:09:59