stdr_gui_robot.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_robot.h"
00023 
00024 namespace stdr_gui
00025 {
00031   CGuiRobot::CGuiRobot(const stdr_msgs::RobotIndexedMsg& msg)
00032   {
00033     robot_initialized_ = false;
00034     started_ = false;
00035     initial_pose_ = msg.robot.initialPose;
00036     current_pose_ = initial_pose_;
00037     footprint_ = msg.robot.footprint;
00038     radius_ = msg.robot.footprint.radius;
00039     frame_id_ = msg.name;
00040     show_label_ = true;
00041     show_circles_ = false;
00042     visualization_status_ = 0;
00043     for(unsigned int i = 0 ; i < msg.robot.laserSensors.size() ; i++)
00044     {
00045       CGuiLaser *l = new CGuiLaser(msg.robot.laserSensors[i], frame_id_);
00046       lasers_.push_back(l);
00047     }
00048     for(unsigned int i = 0 ; i < msg.robot.sonarSensors.size() ; i++)
00049     {
00050       CGuiSonar *l = new CGuiSonar(msg.robot.sonarSensors[i], frame_id_);
00051       sonars_.push_back(l);
00052     }
00053     for(unsigned int i = 0 ; i < msg.robot.rfidSensors.size() ; i++)
00054     {
00055       CGuiRfid *l = new CGuiRfid(msg.robot.rfidSensors[i], frame_id_);
00056       rfids_.push_back(l);
00057     }
00058     for(unsigned int i = 0 ; i < msg.robot.co2Sensors.size() ; i++)
00059     {
00060       CGuiCO2 *l = new CGuiCO2(msg.robot.co2Sensors[i], frame_id_);
00061       co2_sensors_.push_back(l);
00062     }
00063     for(unsigned int i = 0 ; i < msg.robot.thermalSensors.size() ; i++)
00064     {
00065       CGuiThermal *l = new CGuiThermal(msg.robot.thermalSensors[i], frame_id_);
00066       thermal_sensors_.push_back(l);
00067     }
00068     for(unsigned int i = 0 ; i < msg.robot.soundSensors.size() ; i++)
00069     {
00070       CGuiSound *l = new CGuiSound(msg.robot.soundSensors[i], frame_id_);
00071       sound_sensors_.push_back(l);
00072     }
00073     robot_initialized_ = true;
00074   }
00075   
00081   void CGuiRobot::speedsCallback(const geometry_msgs::Twist& msg)
00082   {
00083     linear_speed_ = msg.linear.x;
00084     angular_speed_ = msg.angular.z;
00085   }
00086   
00094   void CGuiRobot::draw(QImage *m,float ocgd,tf::TransformListener *listener)
00095   {
00096     if(!robot_initialized_)
00097     {
00098       return;
00099     }
00100     if(robot_initialized_ && !started_)
00101     {
00102       ros::NodeHandle n_;
00103       std::string speeds_topic = frame_id_ + std::string("/cmd_vel");
00104       speeds_subscriber_ = n_.subscribe(
00105         speeds_topic.c_str(), 
00106         1, 
00107         &CGuiRobot::speedsCallback,
00108         this);
00109     }
00110     started_ = true;
00111     resolution_ = ocgd;
00112     tf::StampedTransform transform;
00113       
00114     try
00115     {
00116       listener->waitForTransform("map_static",
00117                                   frame_id_.c_str(),
00118                                   ros::Time(0),
00119                                   ros::Duration(0.2));
00120       listener->lookupTransform("map_static", 
00121         frame_id_.c_str(), ros::Time(0), transform);
00122     }
00123     catch (tf::TransformException ex)
00124     {
00125       ROS_DEBUG("%s",ex.what());
00126     }
00127     tfScalar roll,pitch,yaw;
00128     current_pose_.x = transform.getOrigin().x();
00129     current_pose_.y = transform.getOrigin().y();
00130     transform.getBasis().getRPY(roll,pitch,yaw);
00131     current_pose_.theta = yaw;
00132     
00133     for(unsigned int i = 0 ; i < lasers_.size() ; i++)
00134     {
00135       lasers_[i]->paint(m,resolution_,listener);
00136     }
00137     for(unsigned int i = 0 ; i < sonars_.size() ; i++)
00138     {
00139       sonars_[i]->paint(m,resolution_,listener);
00140     }
00141     for(unsigned int i = 0 ; i < rfids_.size() ; i++)
00142     {
00143       rfids_[i]->paint(m,resolution_,listener);
00144     }
00145     for(unsigned int i = 0 ; i < co2_sensors_.size() ; i++)
00146     {
00147       co2_sensors_[i]->paint(m,resolution_,listener);
00148     }
00149     for(unsigned int i = 0 ; i < thermal_sensors_.size() ; i++)
00150     {
00151       thermal_sensors_[i]->paint(m,resolution_,listener);
00152     }
00153     for(unsigned int i = 0 ; i < sound_sensors_.size() ; i++)
00154     {
00155       sound_sensors_[i]->paint(m,resolution_,listener);
00156     }
00157     
00158     drawSelf(m);
00159   }
00160   
00166   void CGuiRobot::drawSelf(QImage *m)
00167   {
00168     QPainter painter(m);
00169     painter.setRenderHint(QPainter::Antialiasing, true);
00170     
00171     painter.setPen(QColor(0,0,200,50 + 100 * (2 - visualization_status_)));
00172     
00173     if(footprint_.points.size() == 0)
00174     {
00175       painter.drawEllipse(
00176         (current_pose_.x - radius_) / resolution_,
00177         (current_pose_.y - radius_) / resolution_,
00178         radius_ * 2.0 / resolution_,
00179         radius_ * 2.0 / resolution_);
00180       
00181       painter.drawLine( 
00182         current_pose_.x / resolution_,
00183         current_pose_.y / resolution_,
00184         current_pose_.x / resolution_ + 
00185           radius_ / resolution_ * 1.05 * cos(current_pose_.theta),
00186         current_pose_.y / resolution_ + 
00187           radius_ / resolution_ * 1.05 * sin(current_pose_.theta));
00188     }
00189     else
00190     {
00191       float max = -1;
00192       
00193       static QPointF *points = new QPointF[footprint_.points.size() + 1];
00194       
00195       for(unsigned int i = 0 ; i < footprint_.points.size() + 1; i++)
00196       {
00197         
00198         float x = footprint_.points[i % footprint_.points.size()].x;
00199         float y = footprint_.points[i % footprint_.points.size()].y;
00200         
00201         points[i] = QPointF(
00202           current_pose_.x / resolution_ + 
00203             x / resolution_ * cos(- current_pose_.theta) 
00204             + y / resolution_ * sin(- current_pose_.theta),
00205               
00206           current_pose_.y / resolution_ + 
00207             x / resolution_ * sin(current_pose_.theta) 
00208             + y / resolution_ * cos(- current_pose_.theta));
00209     
00210         if(max < footprint_.points[i].y)
00211         {
00212           max = footprint_.points[i].y;
00213         }
00214         if(max < footprint_.points[i].x)
00215         {
00216           max = footprint_.points[i].x;
00217         }
00218       }
00219       
00220       painter.drawPolyline(points, footprint_.points.size() + 1);
00221       
00222       painter.drawLine(
00223         QPointF(  current_pose_.x / resolution_,
00224                   current_pose_.y / resolution_),
00225         QPointF(  current_pose_.x / resolution_ + 
00226                     max / resolution_ * 1.05 * cos(current_pose_.theta),
00227                   current_pose_.y / resolution_ + 
00228                     max / resolution_ * 1.05 * sin(current_pose_.theta)));
00229     }
00230     
00231     if(show_circles_)
00232     {
00233       painter.setPen(QColor(255,0,0,50 + 100 * (2 - visualization_status_)));
00234       for(unsigned int i = 0 ; i < 5 ; i++)
00235       {
00236         painter.drawEllipse(
00237           (current_pose_.x - (i + 1.0) / 2.0) / resolution_,
00238           (current_pose_.y - (i + 1.0) / 2.0) / resolution_,
00239           (i + 1.0) / resolution_,
00240           (i + 1.0) / resolution_);
00241       }
00242     }
00243   }
00244   
00250   bool CGuiRobot::checkEventProximity(QPoint p)
00251   {
00252     float dx = p.x() * resolution_ - current_pose_.x;
00253     float dy = p.y() * resolution_ - current_pose_.y;
00254     float dist = sqrt( pow(dx,2) + pow(dy,2) );
00255     return dist <= 0.3;
00256   }
00257   
00262   CGuiRobot::~CGuiRobot(void)
00263   {
00264     
00265   }
00266   
00271   void CGuiRobot::destroy(void){
00272     for(unsigned int i = 0 ; i < lasers_.size() ; i++)
00273     {
00274       delete lasers_[i];
00275     }
00276     for(unsigned int i = 0 ; i < sonars_.size() ; i++)
00277     {
00278       delete sonars_[i];
00279     }
00280   }
00281 
00286   std::string CGuiRobot::getFrameId(void)
00287   {
00288     return frame_id_;
00289   }
00290   
00297   void CGuiRobot::drawLabel(QImage *m,float ocgd)
00298   {
00299     QPainter painter(m);
00300     
00301     int text_size = frame_id_.size();
00302     
00303     painter.setPen(QColor(0,0,0,100 * (2 - visualization_status_)));
00304     
00305     painter.drawRect(
00306       current_pose_.x / ocgd + 10,
00307       m->height() - (current_pose_.y / ocgd) - 30,
00308       3 + text_size * 9,
00309       20);
00310     
00311     painter.setPen(QColor(255,255,255,100 * (2 - visualization_status_)));
00312     
00313     painter.fillRect(
00314       current_pose_.x / ocgd + 10,
00315       m->height() - (current_pose_.y / ocgd) - 30,
00316       3 + text_size * 9,
00317       20,
00318       QBrush(QColor(0,0,0,100 * (2 - visualization_status_))));
00319     
00320     painter.setFont(QFont("Courier New"));
00321     painter.drawText(
00322       current_pose_.x / ocgd + 12,
00323       m->height() - (current_pose_.y / ocgd) - 15,
00324       QString(frame_id_.c_str()));
00325   }
00326   
00332   void CGuiRobot::setShowLabel(bool b)
00333   {
00334     show_label_ = b;
00335   }
00336   
00341   bool CGuiRobot::getShowLabel(void)
00342   {
00343     return show_label_;
00344   }
00345   
00350   void CGuiRobot::toggleShowLabel(void)
00351   {
00352     show_label_ =! show_label_;
00353   }
00354   
00359   void CGuiRobot::toggleShowCircles(void)
00360   {
00361     show_circles_ =! show_circles_;
00362   }
00363   
00368   QPoint CGuiRobot::getCurrentPose(void)
00369   {
00370     return QPoint(current_pose_.x / resolution_, 
00371       current_pose_.y / resolution_);
00372   }
00373   
00378   geometry_msgs::Pose2D CGuiRobot::getCurrentPoseM(void)
00379   {
00380     return current_pose_;
00381   }
00382   
00387   int CGuiRobot::getLasersNumber(void)
00388   {
00389     return lasers_.size();
00390   }
00391   
00396   int CGuiRobot::getSonarsNumber(void)
00397   {
00398     return sonars_.size();
00399   }
00400   
00405   QImage CGuiRobot::getVisualization(float ocgd)
00406   {
00407     float maxRange = -1;
00408     for(unsigned int l = 0 ; l < lasers_.size() ; l++)
00409     {
00410       float t = lasers_[l]->getMaxRange();
00411       if(t > maxRange)
00412       {
00413         maxRange = t;
00414       }
00415     }
00416     for(unsigned int l = 0 ; l < sonars_.size() ; l++)
00417     {
00418       float t = sonars_[l]->getMaxRange();
00419       if(t > maxRange)
00420       {
00421         maxRange = t;
00422       }
00423     }
00424     visualization = QImage(310,310,QImage::Format_RGB32);
00425     visualization.fill(Qt::white);
00426     for(unsigned int l = 0 ; l < lasers_.size() ; l++)
00427     {
00428       lasers_[l]->visualizerPaint(&visualization,ocgd,maxRange);
00429     }
00430     for(unsigned int l = 0 ; l < sonars_.size() ; l++)
00431     {
00432       sonars_[l]->visualizerPaint(&visualization,ocgd,maxRange);
00433     }
00434     return visualization;
00435   }
00436   
00442   char CGuiRobot::getLaserVisualizationStatus(std::string frame_id)
00443   {
00444     for(unsigned int i = 0 ; i < lasers_.size() ; i++)
00445     {
00446       if(lasers_[i]->getFrameId() == frame_id)
00447       {
00448         return lasers_[i]->getVisualizationStatus();
00449       }
00450     }
00451     return 0;
00452   }
00453   
00459   char CGuiRobot::getRfidReaderVisualizationStatus(std::string frame_id)
00460   {
00461     for(unsigned int i = 0 ; i < rfids_.size() ; i++)
00462     {
00463       if(rfids_[i]->getFrameId() == frame_id)
00464       {
00465         return rfids_[i]->getVisualizationStatus();
00466       }
00467     }
00468     return 0;
00469   }
00470   
00476   char CGuiRobot::getCO2SensorVisualizationStatus(std::string frame_id)
00477   {
00478     for(unsigned int i = 0 ; i < co2_sensors_.size() ; i++)
00479     {
00480       if(co2_sensors_[i]->getFrameId() == frame_id)
00481       {
00482         return co2_sensors_[i]->getVisualizationStatus();
00483       }
00484     }
00485     return 0;
00486   }
00487   
00493   char CGuiRobot::getThermalSensorVisualizationStatus(std::string frame_id)
00494   {
00495     for(unsigned int i = 0 ; i < thermal_sensors_.size() ; i++)
00496     {
00497       if(thermal_sensors_[i]->getFrameId() == frame_id)
00498       {
00499         return thermal_sensors_[i]->getVisualizationStatus();
00500       }
00501     }
00502     return 0;
00503   }
00504   
00510   char CGuiRobot::getSoundSensorVisualizationStatus(std::string frame_id)
00511   {
00512     for(unsigned int i = 0 ; i < sound_sensors_.size() ; i++)
00513     {
00514       if(sound_sensors_[i]->getFrameId() == frame_id)
00515       {
00516         return sound_sensors_[i]->getVisualizationStatus();
00517       }
00518     }
00519     return 0;
00520   }
00521     
00527   void CGuiRobot::toggleLaserVisualizationStatus(std::string frame_id)
00528   {
00529     for(unsigned int i = 0 ; i < lasers_.size() ; i++)
00530     {
00531       if(lasers_[i]->getFrameId() == frame_id)
00532       {
00533         lasers_[i]->toggleVisualizationStatus();
00534       }
00535     }
00536   }
00537   
00543   char CGuiRobot::getSonarVisualizationStatus(std::string frame_id)
00544   {
00545     for(unsigned int i = 0 ; i < sonars_.size() ; i++)
00546     {
00547       if(sonars_[i]->getFrameId() == frame_id)
00548       {
00549         return sonars_[i]->getVisualizationStatus();
00550       }
00551     }
00552     return 0;
00553   }
00554   
00560   void CGuiRobot::toggleSonarVisualizationStatus(std::string frame_id)
00561   {
00562     for(unsigned int i = 0 ; i < sonars_.size() ; i++)
00563     {
00564       if(sonars_[i]->getFrameId() == frame_id)
00565       {
00566         sonars_[i]->toggleVisualizationStatus();
00567       }
00568     }
00569   }
00570   
00576   void CGuiRobot::toggleRfidReaderVisualizationStatus(std::string frame_id)
00577   {
00578     for(unsigned int i = 0 ; i < rfids_.size() ; i++)
00579     {
00580       if(rfids_[i]->getFrameId() == frame_id)
00581       {
00582         rfids_[i]->toggleVisualizationStatus();
00583       }
00584     }
00585   }
00591   void CGuiRobot::toggleCO2SensorVisualizationStatus(std::string frame_id)
00592   {
00593     for(unsigned int i = 0 ; i < co2_sensors_.size() ; i++)
00594     {
00595       if(co2_sensors_[i]->getFrameId() == frame_id)
00596       {
00597         co2_sensors_[i]->toggleVisualizationStatus();
00598       }
00599     }
00600   }
00606   void CGuiRobot::toggleThermalSensorVisualizationStatus(std::string frame_id)
00607   {
00608     for(unsigned int i = 0 ; i < thermal_sensors_.size() ; i++)
00609     {
00610       if(thermal_sensors_[i]->getFrameId() == frame_id)
00611       {
00612         thermal_sensors_[i]->toggleVisualizationStatus();
00613       }
00614     }
00615   }
00621   void CGuiRobot::toggleSoundSensorVisualizationStatus(std::string frame_id)
00622   {
00623     for(unsigned int i = 0 ; i < sound_sensors_.size() ; i++)
00624     {
00625       if(sound_sensors_[i]->getFrameId() == frame_id)
00626       {
00627         sound_sensors_[i]->toggleVisualizationStatus();
00628       }
00629     }
00630   }
00631   
00636   char CGuiRobot::getVisualizationStatus(void)
00637   {
00638     return visualization_status_;
00639   }
00640   
00645   void CGuiRobot::toggleVisualizationStatus(void)
00646   {
00647     visualization_status_ = (visualization_status_ + 1) % 3;
00648     for(unsigned int i = 0 ; i < lasers_.size() ; i++)
00649     {
00650       lasers_[i]->setVisualizationStatus(visualization_status_);
00651     }
00652     for(unsigned int i = 0 ; i < sonars_.size() ; i++)
00653     {
00654       sonars_[i]->setVisualizationStatus(visualization_status_);
00655     }
00656     for(unsigned int i = 0 ; i < rfids_.size() ; i++)
00657     {
00658       rfids_[i]->setVisualizationStatus(visualization_status_);
00659     }
00660     for(unsigned int i = 0 ; i < co2_sensors_.size() ; i++)
00661     {
00662       co2_sensors_[i]->setVisualizationStatus(visualization_status_);
00663     }
00664     for(unsigned int i = 0 ; i < thermal_sensors_.size() ; i++)
00665     {
00666       thermal_sensors_[i]->setVisualizationStatus(visualization_status_);
00667     }
00668     for(unsigned int i = 0 ; i < sound_sensors_.size() ; i++)
00669     {
00670       sound_sensors_[i]->setVisualizationStatus(visualization_status_);
00671     }
00672   }
00673   
00678   std::pair<float,float> CGuiRobot::getSpeeds(void)
00679   {
00680     return std::pair<float,float>(linear_speed_,angular_speed_);
00681   }
00682   
00688   void CGuiRobot::setEnvironmentalTags(stdr_msgs::RfidTagVector env_tags)
00689   {
00690     for(unsigned int i = 0 ; i < rfids_.size() ; i++)
00691     {
00692       rfids_[i]->setEnvironmentalTags(env_tags);
00693     }
00694   }
00695   
00699   void CGuiRobot::setEnvironmentalCO2Sources(stdr_msgs::CO2SourceVector env_)
00700   {
00701     for(unsigned int i = 0 ; i < co2_sensors_.size() ; i++)
00702     {
00703       co2_sensors_[i]->setEnvironmentalCO2Sources(env_);
00704     }
00705   }
00709   void CGuiRobot::setEnvironmentalThermalSources(stdr_msgs::ThermalSourceVector env_)
00710   {
00711     for(unsigned int i = 0 ; i < thermal_sensors_.size() ; i++)
00712     {
00713       thermal_sensors_[i]->setEnvironmentalThermalSources(env_);
00714     }
00715   }
00719   void CGuiRobot::setEnvironmentalSoundSources(stdr_msgs::SoundSourceVector env_)
00720   {
00721     for(unsigned int i = 0 ; i < sound_sensors_.size() ; i++)
00722     {
00723       sound_sensors_[i]->setEnvironmentalSoundSources(env_);
00724     }
00725   }
00726 }


stdr_gui
Author(s): Manos Tsardoulias
autogenerated on Wed Sep 2 2015 03:36:44