stdr_gui_thermal.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002    STDR Simulator - Simple Two DImensional Robot Simulator
00003    Copyright (C) 2013 STDR Simulator
00004    This program is free software; you can redistribute it and/or modify
00005    it under the terms of the GNU General Public License as published by
00006    the Free Software Foundation; either version 3 of the License, or
00007    (at your option) any later version.
00008    This program is distributed in the hope that it will be useful,
00009    but WITHOUT ANY WARRANTY; without even the implied warranty of
00010    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011    GNU General Public License for more details.
00012    You should have received a copy of the GNU General Public License
00013    along with this program; if not, write to the Free Software Foundation,
00014    Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301  USA
00015    
00016    Authors : 
00017    * Manos Tsardoulias, etsardou@gmail.com
00018    * Aris Thallas, aris.thallas@gmail.com
00019    * Chris Zalidis, zalidis@gmail.com 
00020 ******************************************************************************/
00021 
00022 #include "stdr_gui/stdr_gui_sensors/stdr_gui_thermal.h"
00023 
00024 namespace stdr_gui
00025 {
00029   CGuiThermal::CGuiThermal(stdr_msgs::ThermalSensorMsg msg,std::string baseTopic):
00030     msg_(msg)
00031   {
00032     topic_ = baseTopic + "/" + msg_.frame_id;
00033     tf_frame_ = baseTopic + "_" + msg_.frame_id;
00034     ros::NodeHandle n;
00035     lock_ = false;
00036     subscriber_ = n.subscribe(topic_.c_str(), 1, &CGuiThermal::callback,this);
00037     visualization_status_ = 0;
00038   }
00039   
00043   void CGuiThermal::callback(const stdr_msgs::ThermalSensorMeasurementMsg& msg)
00044   {
00045     if(lock_)
00046     {
00047       return;
00048     }
00049     thermal_sources_ = msg;
00050   }
00051   
00055   void CGuiThermal::paint(
00056     QImage *m,
00057     float ocgd,
00058     tf::TransformListener *listener)
00059   {
00060     lock_ = true;
00061     QPainter painter(m);
00062     
00064     tf::StampedTransform transform;
00065       
00066     try
00067     {
00068       listener->waitForTransform("map_static",
00069                                   tf_frame_.c_str(),
00070                                   ros::Time(0),
00071                                   ros::Duration(0.2));
00072       listener->lookupTransform("map_static", 
00073         tf_frame_.c_str(), ros::Time(0), transform);
00074     }
00075     catch (tf::TransformException ex)
00076     {
00077       ROS_DEBUG("%s",ex.what());
00078     }
00079     tfScalar roll,pitch,yaw;
00080     float pose_x = transform.getOrigin().x();
00081     float pose_y = transform.getOrigin().y();
00082     transform.getBasis().getRPY(roll,pitch,yaw);
00083     float pose_theta = yaw;
00084     
00085     QBrush brush_cone(QColor(100,50,50, 20 * (2 - visualization_status_)));
00086     painter.setBrush(brush_cone);
00087     QPen pen(QColor(0,0,0,0));
00088     painter.setPen(pen);
00089 
00090     painter.drawPie(
00091       pose_x / ocgd - msg_.maxRange / ocgd,
00092         
00093       pose_y / ocgd - msg_.maxRange / ocgd,
00094       
00095       msg_.maxRange / ocgd * 2,
00096       msg_.maxRange / ocgd * 2,
00097       
00098       - (pose_theta - msg_.angleSpan / 2.0)
00099         * 180.0 / STDR_PI * 16,
00100         
00101       - msg_.angleSpan * 180.0 / STDR_PI * 16);
00102 
00103     lock_ = false;
00104   }
00105   
00109   CGuiThermal::~CGuiThermal(void)
00110   {
00111 
00112   }
00113   
00117   char CGuiThermal::getVisualizationStatus(void)
00118   {
00119     return visualization_status_;
00120   }
00121   
00125   void CGuiThermal::toggleVisualizationStatus(void)
00126   {
00127     visualization_status_ = (visualization_status_ + 1) % 3;
00128   }
00129   
00133   void CGuiThermal::setVisualizationStatus(char vs)
00134   {
00135     visualization_status_ = vs;
00136   }
00137   
00142   std::string CGuiThermal::getFrameId(void)
00143   {
00144     return msg_.frame_id;
00145   }
00146   
00152   void CGuiThermal::setEnvironmentalThermalSources(
00153     stdr_msgs::ThermalSourceVector env_thermal_sources)
00154   {
00155     while(lock_)
00156     {
00157       usleep(100);
00158     }
00159     lock_ = true;
00160     env_thermal_sources_ = env_thermal_sources;
00161     lock_ = false;
00162   }
00163 }


stdr_gui
Author(s): Manos Tsardoulias
autogenerated on Thu Jun 6 2019 18:57:38