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_co2.h"
00023
00024 namespace stdr_gui
00025 {
00029 CGuiCO2::CGuiCO2(stdr_msgs::CO2SensorMsg 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, &CGuiCO2::callback,this);
00037 visualization_status_ = 0;
00038 }
00039
00043 void CGuiCO2::callback(const stdr_msgs::CO2SensorMeasurementMsg& msg)
00044 {
00045 if(lock_)
00046 {
00047 return;
00048 }
00049 co2_sources_ = msg;
00050 }
00051
00055 void CGuiCO2::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
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097
00098
00099
00100
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 - 0,
00119
00120 - 2 * 180.0 * 16);
00121
00122 lock_ = false;
00123 }
00124
00128 CGuiCO2::~CGuiCO2(void)
00129 {
00130
00131 }
00132
00136 char CGuiCO2::getVisualizationStatus(void)
00137 {
00138 return visualization_status_;
00139 }
00140
00144 void CGuiCO2::toggleVisualizationStatus(void)
00145 {
00146 visualization_status_ = (visualization_status_ + 1) % 3;
00147 }
00148
00152 void CGuiCO2::setVisualizationStatus(char vs)
00153 {
00154 visualization_status_ = vs;
00155 }
00156
00161 std::string CGuiCO2::getFrameId(void)
00162 {
00163 return msg_.frame_id;
00164 }
00165
00171 void CGuiCO2::setEnvironmentalCO2Sources(
00172 stdr_msgs::CO2SourceVector env_co2_sources)
00173 {
00174 while(lock_)
00175 {
00176 usleep(100);
00177 }
00178 lock_ = true;
00179 env_co2_sources_ = env_co2_sources;
00180 lock_ = false;
00181 }
00182 }