stdr_gui_co2.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  STDR Simulator - Simple Two DImensional Robot Simulator
3  Copyright (C) 2013 STDR Simulator
4  This program is free software; you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation; either version 3 of the License, or
7  (at your option) any later version.
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12  You should have received a copy of the GNU General Public License
13  along with this program; if not, write to the Free Software Foundation,
14  Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
15 
16  Authors :
17  * Manos Tsardoulias, etsardou@gmail.com
18  * Aris Thallas, aris.thallas@gmail.com
19  * Chris Zalidis, zalidis@gmail.com
20 ******************************************************************************/
21 
23 
24 namespace stdr_gui
25 {
29  CGuiCO2::CGuiCO2(stdr_msgs::CO2SensorMsg msg,std::string baseTopic):
30  msg_(msg)
31  {
32  topic_ = baseTopic + "/" + msg_.frame_id;
33  tf_frame_ = baseTopic + "_" + msg_.frame_id;
35  lock_ = false;
36  subscriber_ = n.subscribe(topic_.c_str(), 1, &CGuiCO2::callback,this);
38  }
39 
43  void CGuiCO2::callback(const stdr_msgs::CO2SensorMeasurementMsg& msg)
44  {
45  if(lock_)
46  {
47  return;
48  }
49  co2_sources_ = msg;
50  }
51 
56  QImage *m,
57  float ocgd,
58  tf::TransformListener *listener)
59  {
60  lock_ = true;
61  QPainter painter(m);
62 
64  tf::StampedTransform transform;
65 
66  try
67  {
68  listener->waitForTransform("map_static",
69  tf_frame_.c_str(),
70  ros::Time(0),
71  ros::Duration(0.2));
72  listener->lookupTransform("map_static",
73  tf_frame_.c_str(), ros::Time(0), transform);
74  }
75  catch (tf::TransformException ex)
76  {
77  ROS_DEBUG("%s",ex.what());
78  }
79  tfScalar roll,pitch,yaw;
80  float pose_x = transform.getOrigin().x();
81  float pose_y = transform.getOrigin().y();
82  transform.getBasis().getRPY(roll,pitch,yaw);
83  float pose_theta = yaw;
84 
86  //~ QBrush brush(QColor(50,100,50,75 * (2 - visualization_status_)));
87  //~ painter.setBrush(brush);
88 
89  //~ for(unsigned int j = 0 ; j < co2_sources_.co2_sources_ids.size() ; j++)
90  //~ {
91  //~ for(unsigned int i = 0 ; i < env_co2_sources_.co2_sources.size() ; i++)
92  //~ {
93  //~ if(co2_sources_.co2_sources_ids[j] == env_co2_sources_.co2_sources[i].id)
94  //~ {
95  //~ int x1 = pose_x / ocgd;
96  //~ int y1 = pose_y / ocgd;
97  //~ int x2 = env_co2_sources_.co2_sources[i].pose.x / ocgd;
98  //~ int y2 = env_co2_sources_.co2_sources[i].pose.y / ocgd;
99  //~ painter.drawLine(x1, y1, x2, y2);
100  //~ break;
101  //~ }
102  //~ }
103  //~ }
104 
105  QBrush brush_cone(QColor(50,100,50, 20 * (2 - visualization_status_)));
106  painter.setBrush(brush_cone);
107  QPen pen(QColor(0,0,0,0));
108  painter.setPen(pen);
109 
110  painter.drawPie(
111  pose_x / ocgd - msg_.maxRange / ocgd,
112 
113  pose_y / ocgd - msg_.maxRange / ocgd,
114 
115  msg_.maxRange / ocgd * 2,
116  msg_.maxRange / ocgd * 2,
117 
118  - 0,
119 
120  - 2 * 180.0 * 16);
121 
122  lock_ = false;
123  }
124 
129  {
130 
131  }
132 
137  {
138  return visualization_status_;
139  }
140 
145  {
147  }
148 
153  {
155  }
156 
161  std::string CGuiCO2::getFrameId(void)
162  {
163  return msg_.frame_id;
164  }
165 
172  stdr_msgs::CO2SourceVector env_co2_sources)
173  {
174  while(lock_)
175  {
176  usleep(100);
177  }
178  lock_ = true;
179  env_co2_sources_ = env_co2_sources;
180  lock_ = false;
181  }
182 }
bool lock_
The ROS tf frame.
Definition: stdr_gui_co2.h:51
std::string getFrameId(void)
Returns the frame id of the specific sensor.
double tfScalar
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
TFSIMD_FORCE_INLINE Matrix3x3 & getBasis()
stdr_msgs::CO2SensorMeasurementMsg co2_sources_
The tags that exist in the environment.
Definition: stdr_gui_co2.h:57
stdr_msgs::CO2SourceVector env_co2_sources_
Definition: stdr_gui_co2.h:60
void setEnvironmentalCO2Sources(stdr_msgs::CO2SourceVector env_co2_sources)
Sets the tags existent in the environment.
void toggleVisualizationStatus(void)
Toggles the visibility status of the specific sensor.
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
void setVisualizationStatus(char vs)
Sets the visibility status of the specific sensor.
ros::Subscriber subscriber_
Used to avoid drawing when a new sonar message arives.
Definition: stdr_gui_co2.h:49
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
CGuiCO2(stdr_msgs::CO2SensorMsg msg, std::string baseTopic)
Default contructor.
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
The main namespace for STDR GUI.
void paint(QImage *m, float ocgd, tf::TransformListener *listener)
Paints the rfid measurements in the map image.
~CGuiCO2(void)
Default destructor.
std::string topic_
< The topic from which the new RFID tags will be got
Definition: stdr_gui_co2.h:45
char getVisualizationStatus(void)
Returns the visibility status of the specific sensor.
void callback(const stdr_msgs::CO2SensorMeasurementMsg &msg)
Callback for the rfid measurement message.
std::string tf_frame_
Visualization status of the specific sonar.
Definition: stdr_gui_co2.h:53
stdr_msgs::CO2SensorMsg msg_
A ros subscriber.
Definition: stdr_gui_co2.h:47
char visualization_status_
The stdr rfid sensor measurement msg.
Definition: stdr_gui_co2.h:55
#define ROS_DEBUG(...)


stdr_gui
Author(s): Manos Tsardoulias
autogenerated on Mon Jun 10 2019 15:15:16