Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #include "stdr_gui/stdr_gui_sensors/stdr_gui_rfid.h"
00023
00024 namespace stdr_gui
00025 {
00029 CGuiRfid::CGuiRfid(stdr_msgs::RfidSensorMsg 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, &CGuiRfid::callback,this);
00037 visualization_status_ = 0;
00038 }
00039
00043 void CGuiRfid::callback(const stdr_msgs::RfidSensorMeasurementMsg& msg)
00044 {
00045 if(lock_)
00046 {
00047 return;
00048 }
00049 tags_ = msg;
00050 }
00051
00055 void CGuiRfid::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
00086 QBrush brush(QColor(50,100,50,75 * (2 - visualization_status_)));
00087 painter.setBrush(brush);
00088
00089 for(unsigned int j = 0 ; j < tags_.rfid_tags_ids.size() ; j++)
00090 {
00091 for(unsigned int i = 0 ; i < env_tags_.rfid_tags.size() ; i++)
00092 {
00093 if(tags_.rfid_tags_ids[j] == env_tags_.rfid_tags[i].tag_id)
00094 {
00095 int x1 = pose_x / ocgd;
00096 int y1 = pose_y / ocgd;
00097 int x2 = env_tags_.rfid_tags[i].pose.x / ocgd;
00098 int y2 = env_tags_.rfid_tags[i].pose.y / ocgd;
00099 painter.drawLine(x1, y1, x2, y2);
00100 break;
00101 }
00102 }
00103 }
00104
00105 QBrush brush_cone(QColor(50,100,50, 20 * (2 - visualization_status_)));
00106 painter.setBrush(brush_cone);
00107 QPen pen(QColor(0,0,0,0));
00108 painter.setPen(pen);
00109
00110 painter.drawPie(
00111 pose_x / ocgd - msg_.maxRange / ocgd,
00112
00113 pose_y / ocgd - msg_.maxRange / ocgd,
00114
00115 msg_.maxRange / ocgd * 2,
00116 msg_.maxRange / ocgd * 2,
00117
00118 - (pose_theta - msg_.angleSpan / 2.0)
00119 * 180.0 / STDR_PI * 16,
00120
00121 - msg_.angleSpan * 180.0 / STDR_PI * 16);
00122
00123 lock_ = false;
00124 }
00125
00129 CGuiRfid::~CGuiRfid(void)
00130 {
00131
00132 }
00133
00137 char CGuiRfid::getVisualizationStatus(void)
00138 {
00139 return visualization_status_;
00140 }
00141
00145 void CGuiRfid::toggleVisualizationStatus(void)
00146 {
00147 visualization_status_ = (visualization_status_ + 1) % 3;
00148 }
00149
00153 void CGuiRfid::setVisualizationStatus(char vs)
00154 {
00155 visualization_status_ = vs;
00156 }
00157
00162 std::string CGuiRfid::getFrameId(void)
00163 {
00164 return msg_.frame_id;
00165 }
00166
00172 void CGuiRfid::setEnvironmentalTags(stdr_msgs::RfidTagVector env_tags)
00173 {
00174 while(lock_)
00175 {
00176 usleep(100);
00177 }
00178 lock_ = true;
00179 env_tags_ = env_tags;
00180 lock_ = false;
00181 }
00182 }