stdr_gui_sound.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  CGuiSound::CGuiSound(stdr_msgs::SoundSensorMsg 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, &CGuiSound::callback,this);
38  }
39 
43  void CGuiSound::callback(const stdr_msgs::SoundSensorMeasurementMsg& msg)
44  {
45  if(lock_)
46  {
47  return;
48  }
49  sound_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 
90  // What to draw?
91 
92  //~ for(unsigned int j = 0 ; j < sound_sources_.sound_source_ids.size() ; j++)
93  //~ {
94  //~ for(unsigned int i = 0 ; i < env_sound_sources_.sound_sources.size() ; i++)
95  //~ {
96  //~ if(sound_sources_.sound_sources_ids[j] == env_sound_sources_.sound_sources[i].id)
97  //~ {
98  //~ int x1 = pose_x / ocgd;
99  //~ int y1 = pose_y / ocgd;
100  //~ int x2 = env_sound_sources_.sound_sources[i].pose.x / ocgd;
101  //~ int y2 = env_sound_sources_.sound_sources[i].pose.y / ocgd;
102  //~ painter.drawLine(x1, y1, x2, y2);
103  //~ break;
104  //~ }
105  //~ }
106  //~ }
107 
108  QBrush brush_cone(QColor(50,100,50, 20 * (2 - visualization_status_)));
109  painter.setBrush(brush_cone);
110  QPen pen(QColor(0,0,0,0));
111  painter.setPen(pen);
112 
113  painter.drawPie(
114  pose_x / ocgd - msg_.maxRange / ocgd,
115 
116  pose_y / ocgd - msg_.maxRange / ocgd,
117 
118  msg_.maxRange / ocgd * 2,
119  msg_.maxRange / ocgd * 2,
120 
121  - (pose_theta - msg_.angleSpan / 2.0)
122  * 180.0 / STDR_PI * 16,
123 
124  - msg_.angleSpan * 180.0 / STDR_PI * 16);
125 
126  lock_ = false;
127  }
128 
133  {
134 
135  }
136 
141  {
142  return visualization_status_;
143  }
144 
149  {
151  }
152 
157  {
159  }
160 
165  std::string CGuiSound::getFrameId(void)
166  {
167  return msg_.frame_id;
168  }
169 
176  stdr_msgs::SoundSourceVector env_sound_sources)
177  {
178  while(lock_)
179  {
180  usleep(100);
181  }
182  lock_ = true;
183  env_sound_sources_ = env_sound_sources;
184  lock_ = false;
185  }
186 }
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()
std::string getFrameId(void)
Returns the frame id of the specific sensor.
ros::Subscriber subscriber_
Used to avoid drawing when a new sonar message arives.
std::string tf_frame_
Visualization status of the specific sonar.
char getVisualizationStatus(void)
Returns the visibility status of the specific sensor.
void toggleVisualizationStatus(void)
Toggles the visibility status of the specific sensor.
std::string topic_
< The topic from which the new RFID tags will be got
char visualization_status_
The stdr rfid sensor measurement msg.
void paint(QImage *m, float ocgd, tf::TransformListener *listener)
Paints the rfid measurements in the map image.
bool lock_
The ROS tf frame.
CGuiSound(stdr_msgs::SoundSensorMsg msg, std::string baseTopic)
Default contructor.
stdr_msgs::SoundSensorMeasurementMsg sound_sources_
The tags that exist in the environment.
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 callback(const stdr_msgs::SoundSensorMeasurementMsg &msg)
Callback for the rfid measurement message.
void setEnvironmentalSoundSources(stdr_msgs::SoundSourceVector env_sound_sources)
Sets the tags existent in the environment.
void getRPY(tfScalar &roll, tfScalar &pitch, tfScalar &yaw, unsigned int solution_number=1) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define STDR_PI
Definition: stdr_tools.h:100
~CGuiSound(void)
Default destructor.
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.
stdr_msgs::SoundSensorMsg msg_
A ros subscriber.
stdr_msgs::SoundSourceVector env_sound_sources_
void setVisualizationStatus(char vs)
Sets the visibility status of the specific sensor.
#define ROS_DEBUG(...)


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